mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-12 10:59:59 +03:00
Merge remote-tracking branch 'origin/master' into dzikuvx-speedybee-f405-aio
This commit is contained in:
commit
6e5b32dc56
417 changed files with 129214 additions and 5823 deletions
96
.github/workflows/ci.yml
vendored
96
.github/workflows/ci.yml
vendored
|
@ -2,17 +2,26 @@ name: Build firmware
|
|||
# Don't enable CI on push, just on PR. If you
|
||||
# are working on the main repo and want to trigger
|
||||
# a CI build submit a draft PR.
|
||||
on: pull_request
|
||||
on:
|
||||
pull_request:
|
||||
paths:
|
||||
- 'src/**'
|
||||
- '.github/**'
|
||||
- 'cmake/**'
|
||||
- 'lib/**'
|
||||
- 'docs/Settings.md'
|
||||
- 'CMakeLists.txt'
|
||||
- '*.sh'
|
||||
|
||||
jobs:
|
||||
build:
|
||||
runs-on: ubuntu-latest
|
||||
strategy:
|
||||
matrix:
|
||||
id: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9]
|
||||
id: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15]
|
||||
|
||||
steps:
|
||||
- uses: actions/checkout@v3
|
||||
- uses: actions/checkout@v4
|
||||
- name: Install dependencies
|
||||
run: sudo apt-get update && sudo apt-get -y install ninja-build
|
||||
- name: Setup environment
|
||||
|
@ -31,22 +40,66 @@ jobs:
|
|||
VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }')
|
||||
echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV
|
||||
echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV
|
||||
- uses: actions/cache@v1
|
||||
echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV
|
||||
- uses: actions/cache@v4
|
||||
with:
|
||||
path: downloads
|
||||
key: ${{ runner.os }}-downloads-${{ hashFiles('CMakeLists.txt') }}-${{ hashFiles('**/cmake/*')}}
|
||||
- name: Build targets (${{ matrix.id }})
|
||||
run: mkdir -p build && cd build && cmake -DWARNINGS_AS_ERRORS=ON -DCI_JOB_INDEX=${{ matrix.id }} -DCI_JOB_COUNT=${{ strategy.job-total }} -DBUILD_SUFFIX=${{ env.BUILD_SUFFIX }} -G Ninja .. && ninja ci
|
||||
run: mkdir -p build && cd build && cmake -DWARNINGS_AS_ERRORS=ON -DCI_JOB_INDEX=${{ matrix.id }} -DCI_JOB_COUNT=${{ strategy.job-total }} -DBUILD_SUFFIX=${{ env.BUILD_SUFFIX }} -DMAIN_COMPILE_OPTIONS=-pipe -G Ninja .. && ninja -j${{ env.NUM_CORES }} ci
|
||||
- name: Upload artifacts
|
||||
uses: actions/upload-artifact@v3
|
||||
uses: actions/upload-artifact@v4
|
||||
with:
|
||||
name: matrix-${{ env.BUILD_NAME }}.${{ matrix.id }}
|
||||
path: ./build/*.hex
|
||||
retention-days: 1
|
||||
|
||||
upload-artifacts:
|
||||
runs-on: ubuntu-latest
|
||||
needs: [build]
|
||||
steps:
|
||||
- uses: actions/checkout@v4
|
||||
- name: Setup environment
|
||||
env:
|
||||
ACTIONS_ALLOW_UNSECURE_COMMANDS: true
|
||||
run: |
|
||||
# This is the hash of the commit for the PR
|
||||
# when the action is triggered by PR, empty otherwise
|
||||
COMMIT_ID=${{ github.event.pull_request.head.sha }}
|
||||
# This is the hash of the commit when triggered by push
|
||||
# but the hash of refs/pull/<n>/merge, which is different
|
||||
# from the hash of the latest commit in the PR, that's
|
||||
# why we try github.event.pull_request.head.sha first
|
||||
COMMIT_ID=${COMMIT_ID:-${{ github.sha }}}
|
||||
BUILD_SUFFIX=ci-$(date '+%Y%m%d')-$(git rev-parse --short ${COMMIT_ID})
|
||||
VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }')
|
||||
echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV
|
||||
echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV
|
||||
echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV
|
||||
- name: Download artifacts
|
||||
uses: actions/download-artifact@v4
|
||||
with:
|
||||
pattern: matrix-inav-*
|
||||
merge-multiple: true
|
||||
path: binaries
|
||||
- name: Build target list
|
||||
run: |
|
||||
ls -1 binaries/*.hex | cut -d/ -f2 > targets.txt
|
||||
- name: Upload firmware images
|
||||
uses: actions/upload-artifact@v4
|
||||
with:
|
||||
name: ${{ env.BUILD_NAME }}
|
||||
path: ./build/*.hex
|
||||
path: binaries/*.hex
|
||||
- name: Upload firmware images
|
||||
uses: actions/upload-artifact@v4
|
||||
with:
|
||||
name: targets
|
||||
path: targets.txt
|
||||
|
||||
build-SITL-Linux:
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v3
|
||||
- uses: actions/checkout@v4
|
||||
- name: Install dependencies
|
||||
run: sudo apt-get update && sudo apt-get -y install ninja-build
|
||||
- name: Setup environment
|
||||
|
@ -65,18 +118,19 @@ jobs:
|
|||
VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }')
|
||||
echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV
|
||||
echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV
|
||||
echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV
|
||||
- name: Build SITL
|
||||
run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja .. && ninja
|
||||
run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja .. && ninja -j${{ env.NUM_CORES }}
|
||||
- name: Upload artifacts
|
||||
uses: actions/upload-artifact@v3
|
||||
uses: actions/upload-artifact@v4
|
||||
with:
|
||||
name: ${{ env.BUILD_NAME }}_SITL
|
||||
name: ${{ env.BUILD_NAME }}_SITL-Linux
|
||||
path: ./build_SITL/*_SITL
|
||||
|
||||
build-SITL-Mac:
|
||||
runs-on: macos-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v3
|
||||
- uses: actions/checkout@v4
|
||||
- name: Install dependencies
|
||||
run: |
|
||||
brew install cmake ninja ruby
|
||||
|
@ -97,14 +151,15 @@ jobs:
|
|||
VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }')
|
||||
echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV
|
||||
echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV
|
||||
echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV
|
||||
- name: Build SITL
|
||||
run: |
|
||||
mkdir -p build_SITL && cd build_SITL
|
||||
cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja ..
|
||||
ninja
|
||||
cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -DCMAKE_OSX_ARCHITECTURES="arm64;x86_64" -G Ninja ..
|
||||
ninja -j4
|
||||
|
||||
- name: Upload artifacts
|
||||
uses: actions/upload-artifact@v3
|
||||
uses: actions/upload-artifact@v4
|
||||
with:
|
||||
name: ${{ env.BUILD_NAME }}_SITL-MacOS
|
||||
path: ./build_SITL/*_SITL
|
||||
|
@ -115,7 +170,7 @@ jobs:
|
|||
run:
|
||||
shell: C:\tools\cygwin\bin\bash.exe -o igncr '{0}'
|
||||
steps:
|
||||
- uses: actions/checkout@v3
|
||||
- uses: actions/checkout@v4
|
||||
- name: Setup Cygwin
|
||||
uses: egor-tensin/setup-cygwin@v4
|
||||
with:
|
||||
|
@ -136,20 +191,21 @@ jobs:
|
|||
VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }')
|
||||
echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV
|
||||
echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV
|
||||
|
||||
- name: Build SITL
|
||||
run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja .. && ninja
|
||||
run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja .. && ninja -j4
|
||||
- name: Upload artifacts
|
||||
uses: actions/upload-artifact@v3
|
||||
uses: actions/upload-artifact@v4
|
||||
with:
|
||||
name: ${{ env.BUILD_NAME }}_SITL-WIN
|
||||
path: ./build_SITL/*.exe
|
||||
|
||||
|
||||
test:
|
||||
needs: [build]
|
||||
#needs: [build]
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v3
|
||||
- uses: actions/checkout@v4
|
||||
- name: Install dependencies
|
||||
run: sudo apt-get update && sudo apt-get -y install ninja-build
|
||||
- name: Run Tests
|
||||
|
|
245
.github/workflows/dev-builds.yml
vendored
Normal file
245
.github/workflows/dev-builds.yml
vendored
Normal file
|
@ -0,0 +1,245 @@
|
|||
name: Build pre-release
|
||||
# Don't enable CI on push, just on PR. If you
|
||||
# are working on the main repo and want to trigger
|
||||
# a CI build submit a draft PR.
|
||||
on:
|
||||
push:
|
||||
branches:
|
||||
- master
|
||||
paths:
|
||||
- 'src/**'
|
||||
- '.github/**'
|
||||
- 'cmake/**'
|
||||
- 'lib/**'
|
||||
- 'docs/Settings.md'
|
||||
- 'CMakeLists.txt'
|
||||
- '*.sh'
|
||||
|
||||
jobs:
|
||||
build:
|
||||
runs-on: ubuntu-latest
|
||||
strategy:
|
||||
matrix:
|
||||
id: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15]
|
||||
|
||||
steps:
|
||||
- uses: actions/checkout@v4
|
||||
- name: Install dependencies
|
||||
run: sudo apt-get update && sudo apt-get -y install ninja-build
|
||||
- name: Setup environment
|
||||
env:
|
||||
ACTIONS_ALLOW_UNSECURE_COMMANDS: true
|
||||
run: |
|
||||
# This is the hash of the commit for the PR
|
||||
# when the action is triggered by PR, empty otherwise
|
||||
COMMIT_ID=${{ github.event.pull_request.head.sha }}
|
||||
# This is the hash of the commit when triggered by push
|
||||
# but the hash of refs/pull/<n>/merge, which is different
|
||||
# from the hash of the latest commit in the PR, that's
|
||||
# why we try github.event.pull_request.head.sha first
|
||||
COMMIT_ID=${COMMIT_ID:-${{ github.sha }}}
|
||||
BUILD_SUFFIX=dev-$(date '+%Y%m%d')-$(git rev-parse --short ${COMMIT_ID})
|
||||
VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }')
|
||||
echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV
|
||||
echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV
|
||||
echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV
|
||||
- uses: actions/cache@v4
|
||||
with:
|
||||
path: downloads
|
||||
key: ${{ runner.os }}-downloads-${{ hashFiles('CMakeLists.txt') }}-${{ hashFiles('**/cmake/*')}}
|
||||
- name: Build targets (${{ matrix.id }})
|
||||
run: mkdir -p build && cd build && cmake -DWARNINGS_AS_ERRORS=ON -DCI_JOB_INDEX=${{ matrix.id }} -DCI_JOB_COUNT=${{ strategy.job-total }} -DBUILD_SUFFIX=${{ env.BUILD_SUFFIX }} -DVERSION_TYPE=dev -G Ninja .. && ninja -j${{ env.NUM_CORES }} ci
|
||||
- name: Upload artifacts
|
||||
uses: actions/upload-artifact@v4
|
||||
with:
|
||||
name: ${{ env.BUILD_NAME }}.${{ matrix.id }}
|
||||
path: ./build/*.hex
|
||||
|
||||
build-SITL-Linux:
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v4
|
||||
- name: Install dependencies
|
||||
run: sudo apt-get update && sudo apt-get -y install ninja-build
|
||||
- name: Setup environment
|
||||
env:
|
||||
ACTIONS_ALLOW_UNSECURE_COMMANDS: true
|
||||
run: |
|
||||
# This is the hash of the commit for the PR
|
||||
# when the action is triggered by PR, empty otherwise
|
||||
COMMIT_ID=${{ github.event.pull_request.head.sha }}
|
||||
# This is the hash of the commit when triggered by push
|
||||
# but the hash of refs/pull/<n>/merge, which is different
|
||||
# from the hash of the latest commit in the PR, that's
|
||||
# why we try github.event.pull_request.head.sha first
|
||||
COMMIT_ID=${COMMIT_ID:-${{ github.sha }}}
|
||||
BUILD_SUFFIX=dev-$(date '+%Y%m%d')-$(git rev-parse --short ${COMMIT_ID})
|
||||
VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/[ \t\)]+/, "", $2); print $2 }')
|
||||
echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV
|
||||
echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV
|
||||
echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV
|
||||
- name: Build SITL
|
||||
run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja -DVERSION_TYPE=dev .. && ninja -j${{ env.NUM_CORES }}
|
||||
- name: Upload artifacts
|
||||
uses: actions/upload-artifact@v4
|
||||
with:
|
||||
name: sitl-${{ env.BUILD_NAME }}-Linux
|
||||
path: ./build_SITL/*_SITL
|
||||
|
||||
build-SITL-Mac:
|
||||
runs-on: macos-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v4
|
||||
- name: Install dependencies
|
||||
run: |
|
||||
brew install cmake ninja ruby
|
||||
|
||||
- name: Setup environment
|
||||
env:
|
||||
ACTIONS_ALLOW_UNSECURE_COMMANDS: true
|
||||
run: |
|
||||
# This is the hash of the commit for the PR
|
||||
# when the action is triggered by PR, empty otherwise
|
||||
COMMIT_ID=${{ github.event.pull_request.head.sha }}
|
||||
# This is the hash of the commit when triggered by push
|
||||
# but the hash of refs/pull/<n>/merge, which is different
|
||||
# from the hash of the latest commit in the PR, that's
|
||||
# why we try github.event.pull_request.head.sha first
|
||||
COMMIT_ID=${COMMIT_ID:-${{ github.sha }}}
|
||||
BUILD_SUFFIX=dev-$(date '+%Y%m%d')-$(git rev-parse --short ${COMMIT_ID})
|
||||
VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/[ \t\)]+/, "", $2); print $2 }')
|
||||
echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV
|
||||
echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV
|
||||
- name: Build SITL
|
||||
run: |
|
||||
mkdir -p build_SITL && cd build_SITL
|
||||
cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -DCMAKE_OSX_ARCHITECTURES="arm64;x86_64" -DVERSION_TYPE=dev -G Ninja ..
|
||||
ninja -j4
|
||||
|
||||
- name: Upload artifacts
|
||||
uses: actions/upload-artifact@v4
|
||||
with:
|
||||
name: sitl-${{ env.BUILD_NAME }}-MacOS
|
||||
path: ./build_SITL/*_SITL
|
||||
|
||||
build-SITL-Windows:
|
||||
runs-on: windows-latest
|
||||
defaults:
|
||||
run:
|
||||
shell: C:\tools\cygwin\bin\bash.exe -o igncr '{0}'
|
||||
steps:
|
||||
- uses: actions/checkout@v4
|
||||
- name: Setup Cygwin
|
||||
uses: egor-tensin/setup-cygwin@v4
|
||||
with:
|
||||
packages: cmake ruby ninja gcc-g++
|
||||
- name: Setup environment
|
||||
env:
|
||||
ACTIONS_ALLOW_UNSECURE_COMMANDS: true
|
||||
run: |
|
||||
# This is the hash of the commit for the PR
|
||||
# when the action is triggered by PR, empty otherwise
|
||||
COMMIT_ID=${{ github.event.pull_request.head.sha }}
|
||||
# This is the hash of the commit when triggered by push
|
||||
# but the hash of refs/pull/<n>/merge, which is different
|
||||
# from the hash of the latest commit in the PR, that's
|
||||
# why we try github.event.pull_request.head.sha first
|
||||
COMMIT_ID=${COMMIT_ID:-${{ github.sha }}}
|
||||
BUILD_SUFFIX=dev-$(date '+%Y%m%d')-$(git rev-parse --short ${COMMIT_ID})
|
||||
VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/[ \t\)]+/, "", $2); print $2 }')
|
||||
#echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV
|
||||
#echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV
|
||||
#echo "VERSION_TAG=-$(date '+%Y%m%d')" >> $GITHUB_ENV
|
||||
echo "version=${VERSION}" >> $GITHUB_OUTPUT
|
||||
- name: Build SITL
|
||||
run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -DVERSION_TYPE=dev -G Ninja .. && ninja -j4
|
||||
- name: Upload artifacts
|
||||
uses: actions/upload-artifact@v4
|
||||
with:
|
||||
name: sitl-${{ env.BUILD_NAME }}-WIN
|
||||
path: ./build_SITL/*.exe
|
||||
|
||||
|
||||
test:
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v4
|
||||
- name: Install dependencies
|
||||
run: sudo apt-get update && sudo apt-get -y install ninja-build
|
||||
- name: Run Tests
|
||||
run: mkdir -p build && cd build && cmake -DTOOLCHAIN=none -G Ninja .. && ninja check
|
||||
|
||||
release:
|
||||
needs: [build, build-SITL-Linux, build-SITL-Mac, build-SITL-Windows, test]
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v4
|
||||
- name: Get version
|
||||
id: version
|
||||
run: |
|
||||
VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/[ \t\)]+/, "", $2); print $2 }')
|
||||
echo "version=${VERSION}" >> $GITHUB_OUTPUT
|
||||
- name: Get current date
|
||||
id: date
|
||||
run: echo "today=$(date '+%Y%m%d')" >> $GITHUB_OUTPUT
|
||||
- name: download artifacts
|
||||
uses: actions/download-artifact@v4
|
||||
with:
|
||||
path: hexes
|
||||
pattern: inav-*
|
||||
merge-multiple: true
|
||||
- name: download sitl linux
|
||||
uses: actions/download-artifact@v4
|
||||
with:
|
||||
path: resources/sitl/linux
|
||||
pattern: sitl-*-Linux
|
||||
merge-multiple: true
|
||||
- name: download sitl windows
|
||||
uses: actions/download-artifact@v4
|
||||
with:
|
||||
path: resources/sitl/windows
|
||||
pattern: sitl-*-WIN
|
||||
merge-multiple: true
|
||||
- name: download sitl mac
|
||||
uses: actions/download-artifact@v4
|
||||
with:
|
||||
path: resources/sitl/macos
|
||||
pattern: sitl-*-MacOS
|
||||
merge-multiple: true
|
||||
- name: Consolidate sitl files
|
||||
run: |
|
||||
zip -r -9 sitl-resources.zip resources/
|
||||
- name: Upload release artifacts
|
||||
uses: softprops/action-gh-release@v2
|
||||
with:
|
||||
name: inav-${{ steps.version.outputs.version }}-dev-${{ steps.date.outputs.today }}-${{ github.run_number }}-${{ github.sha }}
|
||||
tag_name: v${{ steps.version.outputs.version }}-${{ steps.date.outputs.today }}.${{ github.run_number }}
|
||||
# To create release on a different repo, we need a token setup
|
||||
token: ${{ secrets.NIGHTLY_TOKEN }}
|
||||
repository: iNavFlight/inav-nightly
|
||||
prerelease: true
|
||||
draft: false
|
||||
#generate_release_notes: true
|
||||
make_latest: false
|
||||
files: |
|
||||
hexes/*.hex
|
||||
sitl-resources.zip
|
||||
body: |
|
||||
${{ steps.notes.outputs.notes }}
|
||||
|
||||
### Flashing
|
||||
These are nightly builds and configuration settings can be added and removed often. Flashing with Full chip erase is strongly recommended to avoid issues.
|
||||
Firmware related issues should be opened in the iNavflight/inav repository, not in inav-nightly.
|
||||
|
||||
### Repository:
|
||||
${{ github.repository }} ([link](${{ github.event.repository.html_url }}))
|
||||
|
||||
### Branch:
|
||||
${{ github.ref_name }} ([link](${{ github.event.repository.html_url }}/tree/${{ github.ref_name }}))
|
||||
|
||||
### Latest changeset:
|
||||
${{ github.event.head_commit.id }} ([link](${{ github.event.head_commit.url }}))
|
||||
|
||||
### Changes:
|
||||
${{ github.event.head_commit.message }}
|
||||
|
2
.github/workflows/docs.yml
vendored
2
.github/workflows/docs.yml
vendored
|
@ -14,7 +14,7 @@ jobs:
|
|||
runs-on: ubuntu-latest
|
||||
|
||||
steps:
|
||||
- uses: actions/checkout@v3
|
||||
- uses: actions/checkout@v4
|
||||
- name: Install dependencies
|
||||
run: sudo apt-get update && sudo apt-get -y install python3-yaml
|
||||
- name: Check that Settings.md is up to date
|
||||
|
|
25
.github/workflows/non-code-change.yaml
vendored
Normal file
25
.github/workflows/non-code-change.yaml
vendored
Normal file
|
@ -0,0 +1,25 @@
|
|||
name: Build firmware
|
||||
# Don't enable CI on push, just on PR. If you
|
||||
# are working on the main repo and want to trigger
|
||||
# a CI build submit a draft PR.
|
||||
on:
|
||||
pull_request:
|
||||
paths-ignore:
|
||||
- 'src/**'
|
||||
- '.github/**'
|
||||
- 'cmake/**'
|
||||
- 'lib/**'
|
||||
- 'docs/Settings.md'
|
||||
- 'CMakeLists.txt'
|
||||
- '*.sh'
|
||||
|
||||
jobs:
|
||||
test:
|
||||
#needs: [build]
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v4
|
||||
- name: Install dependencies
|
||||
run: sudo apt-get update && sudo apt-get -y install ninja-build
|
||||
- name: Run Tests
|
||||
run: mkdir -p build && cd build && cmake -DTOOLCHAIN=none -G Ninja .. && ninja check
|
10
.gitignore
vendored
10
.gitignore
vendored
|
@ -1,10 +1,12 @@
|
|||
*.o
|
||||
.DS_Store
|
||||
*~
|
||||
*.swp
|
||||
*.uvopt
|
||||
*.dep
|
||||
*.bak
|
||||
*.uvgui.*
|
||||
*.ubx
|
||||
.project
|
||||
.settings
|
||||
.cproject
|
||||
|
@ -16,6 +18,8 @@ startup_stm32f10x_md_gcc.s
|
|||
cov-int*
|
||||
/build/
|
||||
/build_SITL/
|
||||
/[hs]itl/
|
||||
/ninja/
|
||||
/obj/
|
||||
/patches/
|
||||
/tools/
|
||||
|
@ -36,3 +40,9 @@ make/local.mk
|
|||
launch.json
|
||||
.vscode/tasks.json
|
||||
.vscode/c_cpp_properties.json
|
||||
|
||||
/cmake-build-debug/
|
||||
|
||||
# Assitnow token and files for test script
|
||||
tokens.yaml
|
||||
*.ubx
|
||||
|
|
1
.vimrc
1
.vimrc
|
@ -5,5 +5,6 @@ set expandtab
|
|||
set bs=2
|
||||
set sw=4
|
||||
set ts=4
|
||||
syn on
|
||||
|
||||
|
||||
|
|
21
.vscode/c_cpp_properties.json
vendored
21
.vscode/c_cpp_properties.json
vendored
|
@ -3,24 +3,19 @@
|
|||
{
|
||||
"name": "Linux",
|
||||
"includePath": [
|
||||
"${workspaceRoot}/src/main/**",
|
||||
"${workspaceRoot}/lib/main/**",
|
||||
"/usr/include/**"
|
||||
"${workspaceRoot}",
|
||||
"${workspaceRoot}/src/main/**"
|
||||
],
|
||||
"browse": {
|
||||
"limitSymbolsToIncludedHeaders": false,
|
||||
"path": [
|
||||
"${workspaceRoot}/src/main/**",
|
||||
"${workspaceRoot}/lib/main/**"
|
||||
"${workspaceRoot}/**"
|
||||
]
|
||||
},
|
||||
"intelliSenseMode": "linux-gcc-arm",
|
||||
"intelliSenseMode": "msvc-x64",
|
||||
"cStandard": "c11",
|
||||
"cppStandard": "c++17",
|
||||
"defines": [
|
||||
"MCU_FLASH_SIZE 512",
|
||||
"USE_NAV",
|
||||
"NAV_FIXED_WING_LANDING",
|
||||
"USE_OSD",
|
||||
"USE_GYRO_NOTCH_1",
|
||||
"USE_GYRO_NOTCH_2",
|
||||
|
@ -34,8 +29,6 @@
|
|||
"USE_RPM_FILTER",
|
||||
"USE_GLOBAL_FUNCTIONS",
|
||||
"USE_DYNAMIC_FILTERS",
|
||||
"USE_IMU_BNO055",
|
||||
"USE_SECONDARY_IMU",
|
||||
"USE_DSHOT",
|
||||
"FLASH_SIZE 480",
|
||||
"USE_I2C_IO_EXPANDER",
|
||||
|
@ -58,10 +51,12 @@
|
|||
"USE_SDCARD",
|
||||
"USE_Q_TUNE",
|
||||
"USE_GYRO_FFT_FILTER",
|
||||
"USE_BARO_DPS310"
|
||||
"USE_BARO_DPS310",
|
||||
"USE_ADAPTIVE_FILTER",
|
||||
"MCU_FLASH_SIZE 1024"
|
||||
],
|
||||
"configurationProvider": "ms-vscode.cmake-tools"
|
||||
}
|
||||
],
|
||||
"version": 4
|
||||
}
|
||||
}
|
||||
|
|
4
.vscode/settings.json
vendored
4
.vscode/settings.json
vendored
|
@ -3,6 +3,8 @@
|
|||
"chrono": "c",
|
||||
"cmath": "c",
|
||||
"ranges": "c",
|
||||
"navigation.h": "c",
|
||||
"rth_trackback.h": "c",
|
||||
"platform.h": "c",
|
||||
"timer.h": "c",
|
||||
"bus.h": "c"
|
||||
|
@ -13,4 +15,4 @@
|
|||
"editor.expandTabs": true,
|
||||
"C_Cpp.clang_format_fallbackStyle": "{ BasedOnStyle: Google, IndentWidth: 4, BreakBeforeBraces: Mozilla }"
|
||||
|
||||
}
|
||||
}
|
8
.vscode/tasks.json
vendored
8
.vscode/tasks.json
vendored
|
@ -4,9 +4,9 @@
|
|||
"version": "2.0.0",
|
||||
"tasks": [
|
||||
{
|
||||
"label": "Build Matek F722-SE",
|
||||
"label": "Build AOCODARCH7DUAL",
|
||||
"type": "shell",
|
||||
"command": "make MATEKF722SE",
|
||||
"command": "make AOCODARCH7DUAL",
|
||||
"group": "build",
|
||||
"problemMatcher": [],
|
||||
"options": {
|
||||
|
@ -14,9 +14,9 @@
|
|||
}
|
||||
},
|
||||
{
|
||||
"label": "Build Matek F722",
|
||||
"label": "Build AOCODARCH7DUAL",
|
||||
"type": "shell",
|
||||
"command": "make MATEKF722",
|
||||
"command": "make AOCODARCH7DUAL",
|
||||
"group": {
|
||||
"kind": "build",
|
||||
"isDefault": true
|
||||
|
|
|
@ -51,7 +51,7 @@ else()
|
|||
endif()
|
||||
endif()
|
||||
|
||||
project(INAV VERSION 7.1.2)
|
||||
project(INAV VERSION 8.0.0)
|
||||
|
||||
enable_language(ASM)
|
||||
|
||||
|
@ -79,6 +79,7 @@ set(COMMON_COMPILE_DEFINITIONS
|
|||
FC_VERSION_MAJOR=${CMAKE_PROJECT_VERSION_MAJOR}
|
||||
FC_VERSION_MINOR=${CMAKE_PROJECT_VERSION_MINOR}
|
||||
FC_VERSION_PATCH_LEVEL=${CMAKE_PROJECT_VERSION_PATCH}
|
||||
FC_VERSION_TYPE="${VERSION_TYPE}"
|
||||
)
|
||||
|
||||
if (NOT SITL)
|
||||
|
|
|
@ -21,7 +21,6 @@ doc_files=(
|
|||
'Buzzer.md'
|
||||
'Sonar.md'
|
||||
'Profiles.md'
|
||||
'Modes.md'
|
||||
'Inflight Adjustments.md'
|
||||
'Controls.md'
|
||||
'Gtune.md'
|
||||
|
@ -49,7 +48,7 @@ if which gimli >/dev/null; then
|
|||
done
|
||||
rm -f ${filename}.pdf
|
||||
gimli -f ${filename}.md -stylesheet override.css \
|
||||
-w '--toc --title "Cleanflight Manual" --footer-right "[page]" --toc-depth 1'
|
||||
-w '--toc --title "INAV Manual" --footer-right "[page]" --toc-depth 1'
|
||||
rm ${filename}.md
|
||||
popd >/dev/null
|
||||
else
|
||||
|
|
|
@ -2,21 +2,18 @@ include(gcc)
|
|||
set(arm_none_eabi_triplet "arm-none-eabi")
|
||||
|
||||
# Keep version in sync with the distribution files below
|
||||
set(arm_none_eabi_gcc_version "10.3.1")
|
||||
set(arm_none_eabi_base_url "https://developer.arm.com/-/media/Files/downloads/gnu-rm/10.3-2021.10/gcc-arm-none-eabi-10.3-2021.10")
|
||||
set(arm_none_eabi_gcc_version "13.2.1")
|
||||
# This is the output directory "pretty" name and URI name prefix
|
||||
set(base_dir_name "arm-gnu-toolchain-13.2.rel1")
|
||||
# This is the name inside the archive, which is no longer evincible from URI, alas
|
||||
set(archive_base_dir_name "arm-gnu-toolchain-13.2.Rel1")
|
||||
set(arm_none_eabi_base_url "https://developer.arm.com/-/media/Files/downloads/gnu/13.2.rel1/binrel/${base_dir_name}")
|
||||
# suffix and checksum
|
||||
set(arm_none_eabi_win32 "win32.zip" 2bc8f0c4c4659f8259c8176223eeafc1)
|
||||
set(arm_none_eabi_linux_amd64 "x86_64-linux.tar.bz2" 2383e4eb4ea23f248d33adc70dc3227e)
|
||||
set(arm_none_eabi_linux_aarch64 "aarch64-linux.tar.bz2" 3fe3d8bb693bd0a6e4615b6569443d0d)
|
||||
set(arm_none_eabi_gcc_macos "mac.tar.bz2" 7f2a7b7b23797302a9d6182c6e482449)
|
||||
|
||||
function(arm_none_eabi_gcc_distname var)
|
||||
string(REPLACE "/" ";" url_parts ${arm_none_eabi_base_url})
|
||||
list(LENGTH url_parts n)
|
||||
math(EXPR last "${n} - 1")
|
||||
list(GET url_parts ${last} basename)
|
||||
set(${var} ${basename} PARENT_SCOPE)
|
||||
endfunction()
|
||||
set(arm_none_eabi_win32 "mingw-w64-i686-arm-none-eabi.zip" 7fd677088038cdf82f33f149e2e943ee)
|
||||
set(arm_none_eabi_linux_amd64 "x86_64-arm-none-eabi.tar.xz" 791754852f8c18ea04da7139f153a5b7)
|
||||
set(arm_none_eabi_linux_aarch64 "aarch64-arm-none-eabi.tar.xz" 5a08122e6d4caf97c6ccd1d29e62599c)
|
||||
set(arm_none_eabi_darwin_amd64 "darwin-x86_64-arm-none-eabi.tar.xz" 41d49840b0fc676d2ae35aab21a58693)
|
||||
set(arm_none_eabi_darwin_aarch64 "darwin-arm64-arm-none-eabi.tar.xz" 2c43e9d72206c1f81227b0a685df5ea6)
|
||||
|
||||
function(host_uname_machine var)
|
||||
# We need to call uname -m manually, since at the point
|
||||
|
@ -47,7 +44,14 @@ function(arm_none_eabi_gcc_install)
|
|||
message("-- no precompiled ${arm_none_eabi_triplet} toolchain for machine ${machine}")
|
||||
endif()
|
||||
elseif(CMAKE_HOST_SYSTEM_NAME STREQUAL "Darwin")
|
||||
set(dist ${arm_none_eabi_gcc_macos})
|
||||
host_uname_machine(machine)
|
||||
if(machine STREQUAL "x86_64" OR machine STREQUAL "amd64")
|
||||
set(dist ${arm_none_eabi_darwin_amd64})
|
||||
elseif(machine STREQUAL "aarch64" OR machine STREQUAL "arm64")
|
||||
set(dist ${arm_none_eabi_darwin_aarch64})
|
||||
else()
|
||||
message("-- no precompiled ${arm_none_eabi_triplet} toolchain for machine ${machine}")
|
||||
endif()
|
||||
endif()
|
||||
|
||||
if(dist STREQUAL "")
|
||||
|
@ -83,11 +87,27 @@ function(arm_none_eabi_gcc_install)
|
|||
if(NOT status EQUAL 0)
|
||||
message(FATAL_ERROR "error extracting ${basename}: ${status}")
|
||||
endif()
|
||||
string(REPLACE "." ";" url_parts ${dist_suffix})
|
||||
list(GET url_parts 0 host_dir_name)
|
||||
set(dir_name "${archive_base_dir_name}-${host_dir_name}")
|
||||
file(REMOVE_RECURSE "${TOOLS_DIR}/${base_dir_name}")
|
||||
file(RENAME "${TOOLS_DIR}/${dir_name}" "${TOOLS_DIR}/${base_dir_name}")
|
||||
# This is **somewhat ugly**
|
||||
# the newlib distributed by ARM generates suprious warnings from re-entrant POSIX functions
|
||||
# that INAV doesn't use. These "harmless" warnings can be surpressed by removing the
|
||||
# errant section from the only libnosys used by INAV ...
|
||||
# So look the other way ... while this is "fixed"
|
||||
execute_process(COMMAND arm-none-eabi-objcopy -w -R .gnu.warning.* "${TOOLS_DIR}/${base_dir_name}/arm-none-eabi/lib/thumb/v7e-m+fp/hard/libnosys.a"
|
||||
RESULT_VARIABLE status
|
||||
WORKING_DIRECTORY ${TOOLS_DIR}
|
||||
)
|
||||
if(NOT status EQUAL 0)
|
||||
message(FATAL_ERROR "error fixing libnosys.a: ${status}")
|
||||
endif()
|
||||
endfunction()
|
||||
|
||||
function(arm_none_eabi_gcc_add_path)
|
||||
arm_none_eabi_gcc_distname(dist_name)
|
||||
set(gcc_path "${TOOLS_DIR}/${dist_name}/bin")
|
||||
set(gcc_path "${TOOLS_DIR}/${base_dir_name}/bin")
|
||||
if(CMAKE_HOST_SYSTEM MATCHES ".*Windows.*")
|
||||
set(sep "\\;")
|
||||
else()
|
||||
|
@ -110,7 +130,7 @@ function(arm_none_eabi_gcc_check)
|
|||
message("-- found ${prog} ${version} at ${prog_path}")
|
||||
if(COMPILER_VERSION_CHECK AND NOT arm_none_eabi_gcc_version STREQUAL version)
|
||||
message("-- expecting ${prog} version ${arm_none_eabi_gcc_version}, but got version ${version} instead")
|
||||
arm_none_eabi_gcc_install()
|
||||
arm_none_eabi_gcc_install()
|
||||
return()
|
||||
endif()
|
||||
endfunction()
|
||||
|
|
|
@ -9,7 +9,7 @@ option(SEMIHOSTING "Enable semihosting")
|
|||
message("-- DEBUG_HARDFAULTS: ${DEBUG_HARDFAULTS}, SEMIHOSTING: ${SEMIHOSTING}")
|
||||
|
||||
set(CMSIS_DIR "${MAIN_LIB_DIR}/lib/main/AT32F43x/Drivers/CMSIS")
|
||||
set(CMSIS_INCLUDE_DIR "${CMSIS_DIR}/cm4/core_support")
|
||||
set(CMSIS_INCLUDE_DIR "${CMSIS_DIR}/cm4/core_support")
|
||||
# DSP use common
|
||||
set(CMSIS_DSP_DIR "${MAIN_LIB_DIR}/main/CMSIS/DSP")
|
||||
set(CMSIS_DSP_INCLUDE_DIR "${CMSIS_DSP_DIR}/Include")
|
||||
|
@ -18,6 +18,7 @@ set(CMSIS_DSP_SRC
|
|||
BasicMathFunctions/arm_scale_f32.c
|
||||
BasicMathFunctions/arm_sub_f32.c
|
||||
BasicMathFunctions/arm_mult_f32.c
|
||||
BasicMathFunctions/arm_offset_f32.c
|
||||
TransformFunctions/arm_rfft_fast_f32.c
|
||||
TransformFunctions/arm_cfft_f32.c
|
||||
TransformFunctions/arm_rfft_fast_init_f32.c
|
||||
|
@ -26,6 +27,9 @@ set(CMSIS_DSP_SRC
|
|||
CommonTables/arm_common_tables.c
|
||||
ComplexMathFunctions/arm_cmplx_mag_f32.c
|
||||
StatisticsFunctions/arm_max_f32.c
|
||||
StatisticsFunctions/arm_rms_f32.c
|
||||
StatisticsFunctions/arm_std_f32.c
|
||||
StatisticsFunctions/arm_mean_f32.c
|
||||
)
|
||||
list(TRANSFORM CMSIS_DSP_SRC PREPEND "${CMSIS_DSP_DIR}/Source/")
|
||||
|
||||
|
@ -50,8 +54,8 @@ main_sources(AT32_ASYNCFATFS_SRC
|
|||
)
|
||||
|
||||
main_sources(AT32_MSC_SRC
|
||||
msc/at32_msc_diskio.c
|
||||
msc/emfat.c
|
||||
msc/at32_msc_diskio.c
|
||||
msc/emfat.c
|
||||
msc/emfat_file.c
|
||||
)
|
||||
|
||||
|
@ -92,6 +96,7 @@ set(AT32_LINK_OPTIONS
|
|||
-Wl,--cref
|
||||
-Wl,--no-wchar-size-warning
|
||||
-Wl,--print-memory-usage
|
||||
-Wl,--no-warn-rwx-segments
|
||||
)
|
||||
# Get target features
|
||||
macro(get_at32_target_features output_var dir target_name)
|
||||
|
@ -264,7 +269,7 @@ function(add_at32_executable)
|
|||
endif()
|
||||
endfunction()
|
||||
|
||||
# Main function of AT32
|
||||
# Main function of AT32
|
||||
function(target_at32)
|
||||
if(NOT arm-none-eabi STREQUAL TOOLCHAIN)
|
||||
return()
|
||||
|
@ -325,6 +330,11 @@ function(target_at32)
|
|||
|
||||
math(EXPR hse_value "${hse_mhz} * 1000000")
|
||||
list(APPEND target_definitions "HSE_VALUE=${hse_value}")
|
||||
|
||||
if (MSP_UART)
|
||||
list(APPEND target_definitions "MSP_UART=${MSP_UART}")
|
||||
endif()
|
||||
|
||||
if(args_COMPILE_DEFINITIONS)
|
||||
list(APPEND target_definitions ${args_COMPILE_DEFINITIONS})
|
||||
endif()
|
||||
|
|
|
@ -99,6 +99,10 @@ function (target_sitl name)
|
|||
math(EXPR hse_value "${hse_mhz} * 1000000")
|
||||
list(APPEND target_definitions "HSE_VALUE=${hse_value}")
|
||||
|
||||
if (MSP_UART)
|
||||
list(APPEND target_definitions "MSP_UART=${MSP_UART}")
|
||||
endif()
|
||||
|
||||
string(TOLOWER ${PROJECT_NAME} lowercase_project_name)
|
||||
set(binary_name ${lowercase_project_name}_${FIRMWARE_VERSION}_${name})
|
||||
if(DEFINED BUILD_SUFFIX AND NOT "" STREQUAL "${BUILD_SUFFIX}")
|
||||
|
|
|
@ -19,6 +19,7 @@ set(CMSIS_DSP_SRC
|
|||
BasicMathFunctions/arm_scale_f32.c
|
||||
BasicMathFunctions/arm_sub_f32.c
|
||||
BasicMathFunctions/arm_mult_f32.c
|
||||
BasicMathFunctions/arm_offset_f32.c
|
||||
TransformFunctions/arm_rfft_fast_f32.c
|
||||
TransformFunctions/arm_cfft_f32.c
|
||||
TransformFunctions/arm_rfft_fast_init_f32.c
|
||||
|
@ -27,6 +28,9 @@ set(CMSIS_DSP_SRC
|
|||
CommonTables/arm_common_tables.c
|
||||
ComplexMathFunctions/arm_cmplx_mag_f32.c
|
||||
StatisticsFunctions/arm_max_f32.c
|
||||
StatisticsFunctions/arm_rms_f32.c
|
||||
StatisticsFunctions/arm_std_f32.c
|
||||
StatisticsFunctions/arm_mean_f32.c
|
||||
)
|
||||
list(TRANSFORM CMSIS_DSP_SRC PREPEND "${CMSIS_DSP_DIR}/Source/")
|
||||
|
||||
|
@ -333,6 +337,11 @@ function(target_stm32)
|
|||
|
||||
math(EXPR hse_value "${hse_mhz} * 1000000")
|
||||
list(APPEND target_definitions "HSE_VALUE=${hse_value}")
|
||||
|
||||
if (MSP_UART)
|
||||
list(APPEND target_definitions "MSP_UART=${MSP_UART}")
|
||||
endif()
|
||||
|
||||
if(args_COMPILE_DEFINITIONS)
|
||||
list(APPEND target_definitions ${args_COMPILE_DEFINITIONS})
|
||||
endif()
|
||||
|
|
|
@ -216,6 +216,7 @@ macro(define_target_stm32h7 subfamily size)
|
|||
COMPILE_DEFINITIONS ${definitions}
|
||||
LINKER_SCRIPT stm32_flash_h7${subfamily}x${size}
|
||||
${${func_ARGV}}
|
||||
SVD STM32H7${subfamily}
|
||||
)
|
||||
endfunction()
|
||||
endmacro()
|
||||
|
|
105015
dev/svd/STM32H743.svd
Normal file
105015
dev/svd/STM32H743.svd
Normal file
File diff suppressed because it is too large
Load diff
26
docs/ADSB.md
Normal file
26
docs/ADSB.md
Normal file
|
@ -0,0 +1,26 @@
|
|||
# ADS-B
|
||||
|
||||
[Automatic Dependent Surveillance Broadcast](https://en.wikipedia.org/wiki/Automatic_Dependent_Surveillance%E2%80%93Broadcast)
|
||||
is an air traffic surveillance technology that enables aircraft to be accurately tracked by air traffic controllers and other pilots without the need for conventional radar.
|
||||
|
||||
## Current state
|
||||
|
||||
OSD can be configured to shows the closest aircraft.
|
||||
|
||||
## Hardware
|
||||
|
||||
All ADSB receivers which can send Mavlink [ADSB_VEHICLE](https://mavlink.io/en/messages/common.html#ADSB_VEHICLE) message are supported
|
||||
|
||||
* [PINGRX](https://uavionix.com/product/pingrx-pro/) (not tested)
|
||||
* [TT-SC1](https://www.aerobits.pl/product/aero/) (tested)
|
||||
|
||||
## TT-SC1 settings
|
||||
* download software for ADSB TT-SC1 from https://www.aerobits.pl/product/aero/ , file Micro_ADSB_App-vX.XX.X_win_setup.zip and install it
|
||||
* connect your ADSB to FC, connect both RX and TX pins
|
||||
* in INAV configurator ports TAB set telemetry MAVLINK, and baudrate 115200
|
||||
* go to CLI in inav configurator and set serialpassthrough for port you connected ADSB ```serialpassthrough [PORT_YOU_SELECTED - 1] 115200 rxtx``` and close configurator
|
||||
* open ADSB program you installed, got to settings and set "telemetry" = MAVLINK,
|
||||
|
||||
PCB board for TT-SC1-B module https://oshwlab.com/error414/adsb-power-board
|
||||

|
||||
|
|
@ -23,7 +23,7 @@ Unassigned slots have rangeStartStep == rangeEndStep. Each element contains the
|
|||
|
||||
| Data | Type | Notes |
|
||||
|------|------|-------|
|
||||
| permanentId | uint8 | See Modes.md for a definition of the permanent ids |
|
||||
| permanentId | uint8 | See [Modes in the wiki](https://github.com/iNavFlight/inav/wiki/Modes) for a definition of the permanent ids |
|
||||
| auxChannelIndex | uint8 | The Aux switch number (indexed from 0) |
|
||||
| rangeStartStep | uint8 | The start value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
|
||||
| rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
|
||||
|
@ -45,7 +45,7 @@ sending this message for all auxiliary slots.
|
|||
| Data | Type | Notes |
|
||||
|------|------|-------|
|
||||
| sequence id | uint8 | A monotonically increasing ID, from 0 to the number of slots -1 |
|
||||
| permanentId | uint8 | See Modes.md for a definition of the permanent ids |
|
||||
| permanentId | uint8 | See [Modes in the wiki](https://github.com/iNavFlight/inav/wiki/Modes) for a definition of the permanent ids |
|
||||
| auxChannelIndex | uint8 | The Aux channel number (indexed from 0) |
|
||||
| rangeStartStep | uint8 | The start value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
|
||||
| rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 |
|
||||
|
@ -157,5 +157,5 @@ INAV.
|
|||
|
||||
See also
|
||||
--------
|
||||
Modes.md describes the user visible implementation for the INAV
|
||||
[The wiki](https://github.com/iNavFlight/inav/wiki/Modes) describes the user visible implementation for the INAV
|
||||
modes extension.
|
||||
|
|
|
@ -201,7 +201,6 @@ Up to 3 battery profiles are supported. You can select the battery profile from
|
|||
- `vbat_max_cell_voltage`
|
||||
- `vbat_warning_cell_voltage`
|
||||
- `vbat_min_cell_voltage`
|
||||
- `battery_capacity_unit`
|
||||
- `battery_capacity`
|
||||
- `battery_capacity_warning`
|
||||
- `battery_capacity_critical`
|
||||
|
@ -253,7 +252,6 @@ feature BAT_PROF_AUTOSWITCH
|
|||
battery_profile 1
|
||||
|
||||
set bat_cells = 3
|
||||
set battery_capacity_unit = MAH
|
||||
set battery_capacity = 2200
|
||||
set battery_capacity_warning = 440
|
||||
set battery_capacity_critical = 220
|
||||
|
@ -262,7 +260,6 @@ set battery_capacity_critical = 220
|
|||
battery_profile 2
|
||||
|
||||
set bat_cells = 4
|
||||
set battery_capacity_unit = MAH
|
||||
set battery_capacity = 1500
|
||||
set battery_capacity_warning = 300
|
||||
set battery_capacity_critical = 150
|
||||
|
|
|
@ -1,50 +0,0 @@
|
|||
# Betaflight 4.3 compatible MSP DisplayPort OSD (DJI O3 "Canvas Mode")
|
||||
|
||||
INAV 6.0 includes a special mode for MSP DisplayPort that supports incomplete implementations of MSP DisplayPort that only support BetaFlight, like the DJI O3 Air Unit. INAV 6.1 expands this to include HD canvas sizes from BetaFlight 4.4.
|
||||
|
||||
Different flight controllers have different OSD symbols and elements and require different fonts. BetaFlight's font is a single page and supports a maximum of 256 glyphs, INAV's font is currently 2 pages and supports up to 512 different glyphs.
|
||||
|
||||
While there is some overlap between the glyphs in BetaFlight and INAV, it is not possible to perform a 1 to 1 mapping for all the them. In cases where there is no suitable glyph in the BetaFlight font, a question mark `?` will be displayed.
|
||||
|
||||
This mode can be enabled by selecting BF43COMPAT or BFHDCOMPAT as video format in the OSD tab of the configurator or by typing the following command on the CLI:
|
||||
|
||||
`set osd_video_system = BF43COMPAT`
|
||||
|
||||
or
|
||||
|
||||
`set osd_video_system = BFHDCOMPAT`
|
||||
|
||||
## Limitations
|
||||
|
||||
* Canvas size needs to be manually changed to HD on the Display menu in DJI's goggles (you may need a firmware update) and set as BFHDCOMPAT in the OSD tab of the configurator.
|
||||
* Unsupported Glyphs show up as `?`
|
||||
|
||||
## FAQ
|
||||
|
||||
### I see a lot of `?` on my OSD.
|
||||
|
||||
That is expected, when your INAV OSD widgets use glyphs that don't have a suitable mapping in BetaFlight's font.
|
||||
|
||||
### Does it work with the G2 and Original Air Unit/Vista?
|
||||
|
||||
Yes.
|
||||
|
||||
### Is this a replacement for WTFOS?
|
||||
|
||||
Not exactly. WTFOS is a full implementation of MSP-Displayport for rooted Air Unit/Vista/Googles V2 and actually works much better than BetaFlight compatibility mode, being able to display all INAV's glyphs.
|
||||
|
||||
### Can INAV fix DJI's product?
|
||||
|
||||
No. OSD renderinng happens on the googles/air unit side of things. Please ask DJI to fix their incomplete MSP DisplayPort implemenation. You can probably request it in [DJI's forum](https://forum.dji.com/forum.php?mod=forumdisplay&fid=129&filter=typeid&typeid=767).
|
||||
|
||||
### BetaFlight X.Y now has more symbols, can you update INAV?
|
||||
|
||||
Maybe. If a future version of BetaFlight includes more Glyphs that can be mapped into INAV it is fairly simple to add the mapping, but the problem with DJI's implemenation persists. Even if we update the mapping, if DJI does not update the fonts on their side the problem will persist.
|
||||
|
||||
### Can you replace glyph `X` with text `x description`?
|
||||
|
||||
While it might technically be possible to replace some glyphs with text in multiple cells, it will introduce a lot of complexity in the OSD rendering and configuration for something we hope is a temporary workaround.
|
||||
|
||||
### Does DJI support Canvas Mode?
|
||||
|
||||
Actually, no. What DJI calls Canvas Mode is actually MSP DisplayPort and is a character based OSD.
|
|
@ -12,6 +12,9 @@ These boards are well tested with INAV and are known to be of good quality and r
|
|||
| [Holybro Kakute H7](https://inavflight.com/shop/s/bg/1914066) | H7 | KAKUTEH7 | All | All | All | All | All | SERIAL, SD |
|
||||
|
||||
It's possible to find more supported and tested boards [here](https://github.com/iNavFlight/inav/wiki/Welcome-to-INAV,-useful-links-and-products)
|
||||
|
||||
There is also a [full list of all supported boards](https://github.com/iNavFlight/inav/wiki/Boards,-Targets-and-PWM-allocations).
|
||||
|
||||
### Boards documentation
|
||||
|
||||
See the [docs/boards](https://github.com/iNavFlight/inav/tree/master/docs/boards) folder for additional information regards to many targets in INAV, to example help in finding pinout and features. _Feel free to help improve the docs._
|
||||
|
|
79
docs/Broken USB recovery.md
Normal file
79
docs/Broken USB recovery.md
Normal file
|
@ -0,0 +1,79 @@
|
|||
# Broken USB recovery
|
||||
|
||||
It is possible to flash INAV without USB over UART 1 or 3.
|
||||
|
||||
## Prerequisites:
|
||||
- USB/UART adapter (FT232, CP2102, etc.)
|
||||
- STM32 Cube Programmer (https://www.st.com/en/development-tools/stm32cubeprog.html)
|
||||
|
||||
To gain access to the FC via Configurator, MSP must be activated on a UART as standard. Some FCs already have this enabled by default, if not a custom firmware must be created.
|
||||
|
||||
The following targets have MSP activated on a UART by default:
|
||||
|
||||
| Target | Standard MSP Port |
|
||||
|-----------| ----------- |
|
||||
| AOCODARCF4V3 | UART5 |
|
||||
| ATOMRCF405NAVI_DELUXE | UART1 |
|
||||
| FF_F35_LIGHTNING | UART1 |
|
||||
| FLYCOLORF7V2 | UART4 |
|
||||
| GEPRCF405_BT_HD | UART5* |
|
||||
| GEPRCF722_BT_HD | UART4* |
|
||||
| IFLIGHT_BLITZ_F7_AIO | UART1 |
|
||||
| JHEMCUF405WING | UART6 |
|
||||
| JHEMCUH743HD | UART4 |
|
||||
| KAKUTEH7 | UART1 and UART2* |
|
||||
| KAKUTEH7WING | UART6 |
|
||||
| MAMBAF405_2022A | UART4 |
|
||||
| MAMBAF405US | UART4 |
|
||||
| MAMBAF722 | UART4 |
|
||||
| MAMBAF722 APP | UART4*|
|
||||
| MAMBAF722WING | UART4 |
|
||||
| MAMBAF722_X8 | UART4 |
|
||||
| MAMBAH743 | UART4* |
|
||||
| MATEKF405SE | UART1 |
|
||||
| NEUTRONRCH743BT | UART3* |
|
||||
| SDMODELH7V1 | UART1 and UART2 |
|
||||
| SKYSTARSH743HD | UART4 |
|
||||
| SPEEDYBEEF4 | UART5* |
|
||||
| SPEEDYBEEF405MINI | UART4* |
|
||||
| SPEEDYBEEF405V3 | UART4* |
|
||||
| SPEEDYBEEF405V4 | UART4* |
|
||||
| SPEEDYBEEF405WING | UART6 |
|
||||
| SPEEDYBEEF7 | UART6 |
|
||||
| SPRACINGF4EVO | UART1 |
|
||||
| TMOTORF7V2 | UART5 |
|
||||
|
||||
(*) No Pads/Pins, Port is used interally (Bluetooth)
|
||||
|
||||
## Custom firmware:
|
||||
|
||||
If the FC does not have MSP activated on a UART by default or does not have a connector for it, a custom firmware must be built.
|
||||
The following procedure describes the process under Windows 10/11:
|
||||
|
||||
Please read [Building in Windows 2010 or 11 with Linux Subsystem](https://github.com/iNavFlight/inav/blob/master/docs/development/Building%20in%20Windows%2010%20or%2011%20with%20Linux%20Subsystem.md)
|
||||
and follow the instructions up to "Building with Make".
|
||||
|
||||
In the step 'prepare build environment' add the option `-DMSP_UART=SERIAL_PORT_USARTX` to `cmake`
|
||||
|
||||
Replace the X in SERIAL_PORT_USARTX with the number of UART/serial port on which MSP is to be activated.
|
||||
|
||||
Example:
|
||||
For UART 2: `cmake -DMSP_UART=SERIAL_PORT_USART2 ..`
|
||||
For UART 3: `cmake -DMSP_UART=SERIAL_PORT_USART3 ..`
|
||||
etc.
|
||||
|
||||
Build the firmware as described in the document above (`make [YOUR_TARGET]`).
|
||||
|
||||
## Flashing via Uart:
|
||||
|
||||
1. Disconnect ALL peripherals and the USB Cable from the FC. To power the FC use a battery or use the 5V provided from the USB/Serial Converter.
|
||||
2. Connect UART 1 or 3 (other UARTS will not work) and GND to the USB/Serial converter (RX -> TX, TX -> RX)
|
||||
3. Keep the boot/dfu button pressed
|
||||
4. Switch on the FC / supply with power
|
||||
5. Start STM32 CubeProgrammer and go to "Erasing & Programming", second option in the menu.
|
||||
6. Select UART (blue dropdown field) and select the COM port of the USB/Serial adapter and press "Connect". The corresponding processor should now be displayed below.
|
||||
7. Click on "Full flash erase". This is also necessary if you are flashing the same firmware version that was previously on the FC, otherwise MSP may not be activated on the UART.
|
||||
8. Under "Download" load the previously created firmware (`INAV_X.X.X_[Your Target].hex`) or the standard firmware if UART is already activated there. The option "Verify programming" is optional but recommended. Make sure that "Skip flash erase while programming" is NOT activated.
|
||||
9. Click "Start Programming"
|
||||
|
||||
After the process is completed, switch the FC off and on again and then the Configurator can connect to the FC via USB/serial adapter and the previously configured UART.
|
|
@ -71,7 +71,7 @@ While connected to the CLI, all Logical Switches are temporarily disabled (5.1.0
|
|||
| `batch` | Start or end a batch of commands |
|
||||
| `battery_profile` | Change battery profile |
|
||||
| `beeper` | Show/set beeper (buzzer) [usage](Buzzer.md) |
|
||||
| `bind_rx` | Initiate binding for RX SPI or SRXL2 |
|
||||
| `bind_rx` | Initiate binding for SRXL2 or CRSF receivers |
|
||||
| `blackbox` | Configure blackbox fields |
|
||||
| `bootlog` | Show boot events |
|
||||
| `color` | Configure colors |
|
||||
|
@ -107,7 +107,7 @@ While connected to the CLI, all Logical Switches are temporarily disabled (5.1.0
|
|||
| `save` | Save and reboot |
|
||||
| `sd_info` | Sdcard info |
|
||||
| `serial` | Configure serial ports. [Usage](Serial.md) |
|
||||
| `serialpassthrough` | Passthrough serial data to port, with `<id> <baud> <mode>`, where `id` is the zero based port index, `baud` is a standard baud rate, and mode is `rx`, `tx`, or both (`rxtx`) |
|
||||
| `serialpassthrough` | Passthrough serial data to port, with `<id> <baud> <mode> <options>`, where `id` is the zero based port index, `baud` is a standard baud rate, mode is `rx`, `tx`, or both (`rxtx`), and options is a short string like `8N1` or `8E2` |
|
||||
| `servo` | Configure servos |
|
||||
| `set` | Change setting with name=value or blank or * for list |
|
||||
| `smix` | Custom servo mixer |
|
||||
|
@ -157,6 +157,8 @@ A shorter form is also supported to enable and disable a single function using `
|
|||
| TELEMETRY_SMARTPORT_MASTER | 23 | 8388608 |
|
||||
| UNUSED | 24 | 16777216 |
|
||||
| MSP_DISPLAYPORT | 25 | 33554432 |
|
||||
| GIMBAL_SERIAL | 26 | 67108864 |
|
||||
| HEADTRACKER_SERIAL | 27 | 134217728 |
|
||||
|
||||
Thus, to enable MSP and LTM on a port, one would use the function **value** of 17 (1 << 0)+(1<<4), aka 1+16, aka 17.
|
||||
|
||||
|
|
|
@ -1,56 +1,59 @@
|
|||
# Profiles
|
||||
# Control Profiles
|
||||
|
||||
A profile is a set of configuration settings.
|
||||
|
||||
Currently three profiles are supported. The default profile is profile `1`.
|
||||
Currently, INAV gives you three control profiles. The default control profile is `1`.
|
||||
|
||||
## Changing profiles
|
||||
## Changing contorl profiles
|
||||
### Stick Commands
|
||||
Profiles can be selected using a GUI or the following stick combinations:
|
||||
Control profiles can be selected using a GUI or the following stick combinations:
|
||||
|
||||
| Profile | Throttle | Yaw | Pitch | Roll |
|
||||
| ------- | -------- | ----- | ------ | ------ |
|
||||
| 1 | Down | Left | Middle | Left |
|
||||
| 2 | Down | Left | Up | Middle |
|
||||
| 3 | Down | Left | Middle | Right |
|
||||
| Profile # | Throttle | Yaw | Pitch | Roll |
|
||||
| -------- | -------- | ----- | ------ | ------ |
|
||||
| 1 | Down | Left | Middle | Left |
|
||||
| 2 | Down | Left | Up | Middle |
|
||||
| 3 | Down | Left | Middle | Right |
|
||||
|
||||
### CLI
|
||||
The CLI `profile` command can also be used to change profiles:
|
||||
The CLI `control_profile` command can also be used to change control profiles:
|
||||
|
||||
```
|
||||
profile <index>
|
||||
control_profile <index>
|
||||
```
|
||||
|
||||
### Programming (4.0.0 onwards)
|
||||
You can change profiles using the programming frame work. This allows a lot of flexability in how you change profiles.
|
||||
You can change control profiles using the programming frame work. This allows a lot of flexability in how you change profiles.
|
||||
|
||||
For example, using a simple switch on channel 15.
|
||||
|
||||
[](https://i.imgur.com/SS9CaaO.png)
|
||||
|
||||
Or using the speed to change profiles. In this example:
|
||||
- when lower than 25 cm/s (basically not flying), profiles are not effected.
|
||||
- Below 2682 cm/s (60 mph | 97 Km/h) use Profile 1
|
||||
- Above 5364 cm/s (120 mph | 193 Km/h) use Profile 3
|
||||
- Between 2683 and 5364 cm/s, use Profile 2
|
||||
Or using the speed to change control profiles. In this example:
|
||||
- when lower than 25 cm/s (basically not flying), control profiles are not effected.
|
||||
- Below 2682 cm/s (60 mph | 97 Km/h) use control profile 1
|
||||
- Above 5364 cm/s (120 mph | 193 Km/h) use control profile 3
|
||||
- Between 2683 and 5364 cm/s, use control profile 2
|
||||
|
||||
[](https://i.imgur.com/WjkuhhW.png)
|
||||
|
||||
#### Configurator use with profile changing logic.
|
||||
> [!NOTE]
|
||||
> From INAV 8.0, the programming framework operator is **Set Control Profile** and the **Flight** Operand is **Active Control Profile**. Pre-INAV 8.0, they were **Set Profile** and **Active Profile** respectively.
|
||||
|
||||
If you have logic conditions that change the profiles. You may find that if you manually change the profile using the drop down boxes in the top right of Configurator; that they switch back to a different profile. This is because the logic conditions are still running in the background. If this is the case, the simplest solutuion is to temporarily disable the switches that trigger the `set profile` operations. Remember to re-enable these switches after you have made your changes.
|
||||
#### Configurator use with control profile changing logic.
|
||||
|
||||
If you have logic conditions that change the profiles. You may find that if you manually change the control profile; using the drop down boxes in the top right of Configurator. That they switch back to a different control profile. This is because the logic conditions are still running in the background. If this is the case, the simplest solutuion is to temporarily disable the switches that trigger the `Set Control Profile` operations. Remember to re-enable these switches after you have made your changes.
|
||||
|
||||
[](https://i.imgur.com/AeH9ll7.png)
|
||||
|
||||
## Profile Contents
|
||||
The values contained within a profile can be seen by using the CLI `dump profile` command.
|
||||
The values contained within a control profile can be seen by using the CLI `dump control_profile` command.
|
||||
|
||||
e.g
|
||||
```
|
||||
# dump profile
|
||||
# dump control_profile
|
||||
|
||||
# profile
|
||||
profile 1
|
||||
# control_profile
|
||||
control_profile 1
|
||||
|
||||
set mc_p_pitch = 40
|
||||
set mc_i_pitch = 30
|
|
@ -23,9 +23,9 @@ The stick positions are combined to activate different functions:
|
|||
|
||||
| Function | Throttle | Yaw | Pitch | Roll |
|
||||
| ----------------------------- | -------- | ------- | ------ | ------ |
|
||||
| Profile 1 | LOW | LOW | CENTER | LOW |
|
||||
| Profile 2 | LOW | LOW | HIGH | CENTER |
|
||||
| Profile 3 | LOW | LOW | CENTER | HIGH |
|
||||
| Control Profile 1 | LOW | LOW | CENTER | LOW |
|
||||
| Control Profile 2 | LOW | LOW | HIGH | CENTER |
|
||||
| Control Profile 3 | LOW | LOW | CENTER | HIGH |
|
||||
| Battery profile 1 | HIGH | LOW | CENTER | LOW |
|
||||
| Battery profile 2 | HIGH | LOW | HIGH | CENTER |
|
||||
| Battery profile 3 | HIGH | LOW | CENTER | HIGH |
|
||||
|
|
50
docs/DJI compatible OSD.md
Normal file
50
docs/DJI compatible OSD.md
Normal file
|
@ -0,0 +1,50 @@
|
|||
# DJI compatible MSP DisplayPort OSD (DJI O3 "Canvas Mode")
|
||||
|
||||
INAV 6.0 includes a special mode for MSP DisplayPort that supports DJI's incomplete implementations of MSP DisplayPort. This can be found on products like the DJI O3 Air Unit. INAV 6.1 expands this to include HD canvas sizes from BetaFlight 4.4.
|
||||
|
||||
Different flight controller firmware have different OSD symbols and elements and require different fonts. BetaFlight's font is a single page and supports a maximum of 256 glyphs, INAV's font is currently 2 pages and supports up to 512 different glyphs. DJI's font is single page and based, but not the same as, BetaFlight's font.
|
||||
|
||||
While there is some overlap between the glyphs in DJI and INAV, it is not possible to perform a 1 to 1 mapping for all the them. In cases where there is no suitable glyph in the DJI font, a question mark `?` will be displayed.
|
||||
|
||||
This mode can be enabled by selecting DJI43COMPAT or DJIHDCOMPAT as video format in the OSD tab of the configurator or by typing the following command on the CLI:
|
||||
|
||||
`set osd_video_system = DJI43COMPAT`
|
||||
|
||||
or
|
||||
|
||||
`set osd_video_system = DJIHDCOMPAT`
|
||||
|
||||
## Limitations
|
||||
|
||||
* Canvas size needs to be manually changed to HD on the Display menu in DJI's goggles (you may need a firmware update) and set as DJIHDCOMPAT in the OSD tab of the configurator.
|
||||
* Unsupported Glyphs show up as `?`
|
||||
|
||||
## FAQ
|
||||
|
||||
### I see a lot of `?` on my OSD.
|
||||
|
||||
That is expected. When your INAV OSD widgets use glyphs that don't have a suitable mapping in DJI's font.
|
||||
|
||||
### Does it work with the G2 and Original Air Unit/Vista?
|
||||
|
||||
Yes.
|
||||
|
||||
### Is this a replacement for WTFOS?
|
||||
|
||||
Not exactly. WTFOS is a full implementation of MSP-Displayport for rooted Air Unit/Vista/Googles V2 and actually works much better than DJI compatibility mode. It can use all of INAV's OSD elements as intended. If you have the option of WTFOS or DJI compatability mode. WTFOS is the best option.
|
||||
|
||||
### Can INAV fix DJI's product?
|
||||
|
||||
No. OSD renderinng happens on the googles/air unit side of things. Please ask DJI to fix their incomplete MSP DisplayPort implemenation. You can probably request it in [DJI's forum](https://forum.dji.com/forum.php?mod=forumdisplay&fid=129&filter=typeid&typeid=767). To see what you're missing out on with O3. Check out what WTFOS did with the original system. Not only could the pilots upload the fonts of their choosing (who doesn't want a cool SneakyFPV font on their OSD). But there were no problems supporting and firmware. Plus, there was even an option to save the OSD to a file and overlay that over your DVR video. If you're reading this far. Please recommend to DJI that they fix their product, to at least what was possible with WTFOS.
|
||||
|
||||
### DJI's font now has more symbols, can you update INAV?
|
||||
|
||||
Maybe. If a future version of DJI's font includes more Glyphs that can be mapped into INAV. It is fairly simple to add the mapping. However, the best solution would be full support of MSP DisplayPort by DJI. Then there will never be an issue with missing icons. As the latest INAV font would be able to be uploaded on to the goggles.
|
||||
|
||||
### Can you replace glyph `X` with text `x description`?
|
||||
|
||||
While it might technically be possible to replace some glyphs with text in multiple cells, it will introduce a lot of complexity in the OSD rendering and configuration for something we hope is a temporary workaround.
|
||||
|
||||
### Does DJI support Canvas Mode?
|
||||
|
||||
Actually, no. What DJI calls Canvas Mode is actually MSP DisplayPort and is a character based OSD. Currently, the only true implementaion of Canvas Mode is with FrSKY PixelOSD. This was found on some F722 flight controllers from Matek.
|
|
@ -13,7 +13,7 @@ INAV support the following ESC protocols:
|
|||
|
||||
ESC protocol can be selected in Configurator. No special configuration is required.
|
||||
|
||||
Check ESC documentation of the list of protocols that it is supporting.
|
||||
Check the ESC documentation for the list of protocols that are supported.
|
||||
|
||||
## Servo outputs
|
||||
|
||||
|
@ -28,23 +28,8 @@ While motors are usually ordered sequentially, here is no standard output layout
|
|||
|
||||
## Modifying output mapping
|
||||
|
||||
### Modifying all outputs at the same time
|
||||
|
||||
Since INAV 5, it has been possible to force *ALL* outputs to be `MOTORS` or `SERVOS`.
|
||||
|
||||
Traditional ESCs usually can be controlled via a servo output, but would require calibration.
|
||||
|
||||
This can be done with the `output_mode` CLI setting. Allowed values:
|
||||
|
||||
* `AUTO` assigns outputs according to the default mapping
|
||||
* `SERVOS` assigns all outputs to servos
|
||||
* `MOTORS` assigns all outputs to motors
|
||||
|
||||
### Modifying only some outputs
|
||||
|
||||
INAV 7 introduced extra functionality that let you force only some outputs to be either *MOTORS* or *SERVOS*, with some restrictions dictated by the hardware.
|
||||
|
||||
The mains restrictions is that outputs need to be associated with timers, which are usually shared between multiple outputs. Two outputs on the same timer need to have the same function.
|
||||
The main restrictions is that outputs are associated with timers, which can be shared between multiple outputs and two outputs on the same timer need to have the same function.
|
||||
|
||||
The easiest way to modify outputs, is to use the Mixer tab in the Configurator, as it will clearly show you which timer is used by all outputs, but you can also use `timer_output_mode` on the cli.
|
||||
This can be used in conjunction to the previous method, in that cass all outputs will follow `output_mode` and `timer_output_mode` overrides are applied after that.
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
|
||||
INAV supports advanced automatic landings for fixed wing aircraft from version 7.1.
|
||||
The procedure is based on landings for man-carrying aircraft, so that safe landings at a specific location are possible.
|
||||
Supported are landings at safehome after "Return to Home" or at a defined LAND waypoint for missions.
|
||||
Supported are landings at Safehome after "Return to Home" or at a defined LAND waypoint for missions.
|
||||
Every landing locations can be defined with a target point and 2 different approach headings (colinear to the landing strips) with exclusive direction or opposite directions allowed.
|
||||
This enables up to 4 different approach directions, based on the landing site and surrounding area.
|
||||
|
||||
|
@ -15,7 +15,7 @@ This enables up to 4 different approach directions, based on the landing site an
|
|||
3. The landing direction and the approach waypoints are calculated on the basis of the measured wind parameters. If no headwind landing is possible or the wind strength is greater than "Max. tailwind" (see Global Parameters), return to point 2.
|
||||
4. The landing is initiated. The aircraft flies the downwind course, "Approach Altitude" is held.
|
||||
5. Base Leg: the altitude is reduced from 2/3 of "Approach Altitude".
|
||||
6. Final Appraoch: The engine power is reduced using "Pitch2throttle modifier" to reduce speed and the altitude is reduced to "Land Altitude".
|
||||
6. Final Appraoch: The engine power is reduced using "Pitch2throttle modifier" to reduce speed and the altitude is gradually reduced towards "Land Altitude" while approaching the Safehome coordinates.
|
||||
7. Glide: When "Glide Altitude" is reached, the motor is switched off and the pitch angle of "Glide Pitch" is held.
|
||||
7. Flare: Only if a LIDAR/Rangefinder sensor is present: the motor remains switched off and the pitch angle of "Flare Pitch" is held
|
||||
8. Landing: As soon as INAV has detected the landing, it is automatically disarmed, see setting `nav_disarm_on_landing`.
|
||||
|
@ -82,6 +82,23 @@ In degrees. Min: 0, Max: 45, Default: 0
|
|||
* `nav_fw_land_max_tailwind`: Max. tailwind if no landing direction with downwind is available. Wind strengths below this value are ignored (error tolerance in the wind measurement). Landing then takes place in the main direction. If, for example, 90 degrees is configured, landing takes place in this direction, NOT in 270 degrees (see above).
|
||||
In cm/s. Min: 0; Max: 3000, Default: 140
|
||||
|
||||
### General paramters and tuning tips
|
||||
|
||||
* `nav_fw_wp_tracking_accuracy`: Its highly recommended that this parameter is used and tuned well. Only with WP-Tracking enabled, the Aircraft will try to precisely align with the runway during approach.
|
||||
If WP-Tracking is not used, the Plane will head straight to the landiung location without flying in line with the intended landing strip. Wind can intensively alter the final landing heading.
|
||||
|
||||
* `nav_fw_pitch2thr`: The navigation throttle modifier has to be tuned well to allow stable navigation during climbs and descents to prevent a stall. Make sure your plane maintains Ground or Airspeed, when climbing in any navigation mode.
|
||||
The Craft should not get slower and not speed ub significantly during a navigation climb, if P2T is tuned properly.
|
||||
|
||||
* `nav_wp_radius`: This parameter might be too high if you have set up your craft with INAV 6 or INAV 7. With a too high value, the turning points for the Crosswind-Leg and Final Approach are hit too early and make it difficult for the plane to align to the runway or cut short the approach.
|
||||
Make sure this parameter is not set greater than 1000 (cm). The better your craft and navigation system is tuned, the lower this value can be. We recommend to start with 1000 for flying wings and 800 for a Plane with Tail.
|
||||
|
||||
* Test your Navigation-Tuning: A better Navigation-Tune will reward you with smoother and more reliable landings. To test your nav systems limit, we recommend to create a waypoint missions with many 90° turn angles with shorter and shorter tracks.
|
||||
With this Method, you can find out how well your plane can follow a navigation path and how long it takes to align to a waypoint track. A well tuned plane should be able to pull of a WP Mission that looks like this, where the distance between WP6 and WP7 si recommended to be the minimum approach length:
|
||||
|
||||

|
||||
|
||||
|
||||
## Waypoint missions
|
||||
|
||||
Only one landing waypoint per mission can be active and saved and the landing waypoint must be the last waypoint of the mission.
|
||||
|
|
132
docs/GPS_fix_estimation.md
Normal file
132
docs/GPS_fix_estimation.md
Normal file
|
@ -0,0 +1,132 @@
|
|||
# GPS Fix estimation (dead reconing, RTH without GPS) for fixed wing
|
||||
|
||||
Video demonstration
|
||||
|
||||
[](https://www.youtube.com/watch?v=wzvgRpXCS4U)
|
||||
|
||||
There is possibility to allow plane to estimate it's position when GPS fix is lost.
|
||||
The main purpose is RTH without GPS.
|
||||
It works for fixed wing only.
|
||||
|
||||
Plane should have the following sensors:
|
||||
- acceleromenter, gyroscope
|
||||
- barometer
|
||||
- GPS
|
||||
- magnethometer (optional, highly recommended)
|
||||
- pitot (optional)
|
||||
|
||||
By befault, all navigation modes are disabled when GPS fix is lost. If RC signal is lost also, plane will not be able to enable RTH. Plane will switch to LANDING instead. When flying above unreachable spaces, plane will be lost.
|
||||
|
||||
GPS fix estimation allows to recover plane using magnetometer and baromener only.
|
||||
|
||||
GPS Fix is also estimated on GPS Sensor timeouts (hardware failures).
|
||||
|
||||
Note, that GPS fix estimation is not a solution for navigation without GPS. Without GPS fix, position error accumulates quickly. But it is acceptable for RTH. This is not a solution for flying under spoofing also. GPS is the most trusted sensor in Inav. It's output is not validated.
|
||||
|
||||
# How it works ?
|
||||
|
||||
In normal situation, plane is receiving it's position from GPS sensor. This way it is able to hold course, RTH or navigate by waypoints.
|
||||
|
||||
Without GPS fix, plane has nose heading from magnetometer and height from barometer only.
|
||||
|
||||
To navigate without GPS fix, we make the following assumptions:
|
||||
- plane is flying in the direction where nose is pointing
|
||||
- (if pitot tube is not installed) plane is flying with constant airspeed, specified in settings
|
||||
|
||||
It is possible to roughly estimate position using theese assumptions. To increase accuracy, plane will use information about wind direction and speed, estimated before GPS fix was lost. To increase groundspeed estimation accuracy, plane will use pitot tube data(if available).
|
||||
|
||||
From estimated heading direction and speed, plane is able to **roughly** estimate it's position.
|
||||
|
||||
It is assumed, that plane will fly in roughly estimated direction to home position untill either GPS fix or RC signal is recovered.
|
||||
|
||||
*Plane has to acquire GPS fix and store home position before takeoff. Estimation completely without GPS fix will not work*.
|
||||
|
||||
# Estimation without magnethometer
|
||||
|
||||
Without magnethometer, navigation accuracy is very poor. The problem is heading drift.
|
||||
|
||||
The longer plane flies without magnethometer or GPS, the bigger is course estimation error.
|
||||
|
||||
After few minutes and few turns, "North" direction estimation can be completely broken.
|
||||
In general, accuracy is enough to perform RTH U-turn when both RC controls and GPS are lost, and roughtly keep RTH direction in areas with occasional GPS outages.
|
||||
|
||||

|
||||
|
||||
(purple line - estimated position, black line - real position).
|
||||
|
||||
It is recommened to use GPS fix estimation without magnethometer as last resort only. For example, if plane is flying above lake, landing means loss of plane. With GPS Fix estimation, plane will try to do RTH in very rought direction, instead of landing.
|
||||
|
||||
It is up to user to estimate the risk of fly-away.
|
||||
|
||||
|
||||
# Settings
|
||||
|
||||
GPS Fix estimation is enabled with CLI command:
|
||||
|
||||
```set inav_allow_gps_fix_estimation=ON```
|
||||
|
||||
Also you have to specify cruise airspeed of the plane.
|
||||
|
||||
To find out cruise airspeed, make a test flight. Enable ground speed display on OSD. Flight in CRUISE mode in two opposite directions. Take average speed.
|
||||
|
||||
Cruise airspeed is specified in cm/s.
|
||||
|
||||
To convert km/h to m/s, multiply by 27.77.
|
||||
|
||||
|
||||
Example: 100 km/h = 100 * 27.77 = 2777 cm/s
|
||||
|
||||
```set fw_reference_airspeed=2777```
|
||||
|
||||
*It is important, that plane fly with specified speed in CRUISE mode. If you have set option "Increase cruise speed with throttle" - do not use it without GPS Fix.*
|
||||
|
||||
*If pitot is available, pitot sensor data will be used instead of constant. It is not necessary to specify fw_reference_airspeed. However, it is still adviced to specify for the case of pitot failure.*
|
||||
|
||||
*Note related command: to continue mission without RC signal, see command ```set failsafe_mission_delay=-1```.*
|
||||
|
||||
**After entering CLI command, make sure that settings are saved:**
|
||||
|
||||
```save```
|
||||
|
||||
# Disabling GPS sensor from RC controller
|
||||
|
||||

|
||||
|
||||
For testing purposes, it is possible to disable GPS sensor fix from RC controller in programming tab:
|
||||
|
||||
*GPS can be disabled only after: 1) initial GPS fix is acquired 2) in ARMED mode.*
|
||||
|
||||
# Allowing wp missions with GPS Fix estimation
|
||||
|
||||
```failsafe_gps_fix_estimation_delay```
|
||||
|
||||
Controls whether waypoint mission is allowed to proceed with gps fix estimation. Sets the time delay in seconds between gps fix lost event and RTH activation. Minimum delay is 7 seconds. If set to -1 the mission will continue until the end. With default setting(7), waypoint mission is aborted and switched to RTH with 7 seconds delay. RTH is done with GPS Fix estimation. RTH is trigerred regradless of failsafe procedure selected in configurator.
|
||||
|
||||
# Expected error (mag + baro)
|
||||
|
||||
Realistic expected error is up to 200m per 1km of flight path. In tests, 500m drift per 5km path was seen.
|
||||
|
||||
To dicrease drift:
|
||||
- fly one large circle with GPS available to get good wind estimation
|
||||
- use airspeed sensor. If airspeed sensor is not installed, fly in cruise mode without throttle override.
|
||||
- do smooth, large turns
|
||||
- make sure compass is pointing in nose direction precicely
|
||||
- calibrate compass correctly
|
||||
|
||||
This video shows real world test where GPS was disabled occasionally. Wind is 10km/h south-west:
|
||||
|
||||
|
||||
https://github.com/RomanLut/inav/assets/11955117/0599a3c3-df06-4d40-a32a-4d8f96140592
|
||||
|
||||
|
||||
Purple line shows estimated position. Black line shows real position. "EST ERR" sensor shows estimation error in metters. Estimation is running when satellite icon displays "ES". Estimated position snaps to real position when GPS fix is reaquired.
|
||||
|
||||
|
||||
# Is it possible to implement this for multirotor ?
|
||||
|
||||
There are some ideas, but there is no solution now. We can not make assumptions with multirotor which we can make with a fixed wing.
|
||||
|
||||
|
||||
# Links
|
||||
|
||||
INAV HITL https://github.com/RomanLut/INAV-X-Plane-HITL
|
135
docs/Geozones.md
Normal file
135
docs/Geozones.md
Normal file
|
@ -0,0 +1,135 @@
|
|||
# Geozones
|
||||
|
||||
## Introduction
|
||||
The Geozone feature allows pilots to define one or multiple areas on the map in Mission Control, to prevent accidental flying outside of allowed zones (Flight-Zones, FZ) or to avoid certain areas they are not allowed or not willing to fly in (No-Flight-Zone, NFZ).
|
||||
This type of feature might be known to many pilots as a "Geofence" and despite providing the same core functionality, INAV Geozones are significantly more versatile and provide more safety and features.
|
||||
|
||||
Geozones can not only inform the Pilot on the OSD, if the aircraft is approaching a geozone border, it also gives the distance and direction to the closest border and the remaining flight distance to the breach point. Additionally, it provides autonomous avoidance features, if the Aircraft is in any kind of self-leveling flight mode.
|
||||
The most important feature for safety is the automatic path planning for RTH (Start Return To Home), that automatically avoids NFZ areas if possible.
|
||||
|
||||

|
||||
|
||||
|
||||
## Compatibility
|
||||
- [INAV Version: 8.0 or later](https://github.com/iNavFlight/inav/releases)
|
||||
- [INAV Configurator: 8.0 or Later](https://github.com/iNavFlight/inav-configurator/releases)
|
||||
- [MWPTools: Snapshot 2024-11-15 or later](https://github.com/stronnag/mwptools)
|
||||
- Only flight controller with more than 512k of Flash (STM32F405, STM32F765, STM32H743, etc.)
|
||||
- Plane, Multirotor (Rover and Boat are untested at time of writing)
|
||||
|
||||
## Setup Procedure
|
||||
- In the INAV Configurator, switch to the Configuration Panel and enable "Geozone" in the features.
|
||||
- Switch to the Mission Control Panel and you will see a new Icon to call up the Geozone Editor. If Zones are already set up, they will be loaded automatically, as soon as you enter Mission Control.
|
||||

|
||||
- Click on the "+" Symbol to add a new zone and define its parameters to your desire.
|
||||
- The following Options are available:
|
||||
- Shape: Configures a Zone as a Circle or a Polygon
|
||||
- Type: Inclusive (FZ, green) or Exclusive (NFZ, red)
|
||||
- Min. Alt (cm): lower ceiling of the Zone (0 represents the ground relative from the launch location or AMSL. No action will be taken at a minimum altitude of 0, so the aircraft can "dive out" of an Inclusive FZ on a hill. To have a Minimum Altitude action, set a negative altitude of -1 or lower)
|
||||
- Max. Alt (cm): upper ceiling of the Zone (A value if 0 means no upper altitude limit)
|
||||
- Action: Action to execute if an aircraft approaches the border of that Zone
|
||||
- Radius: Circular Zone only, Radius of the Circle
|
||||
- Move the Zone-Markers to the desired locations, to create a bordered area with the shape and size needed (Or change the radius in case of a Circular Zone)
|
||||
- To add additional vertices, click on the borderline of the zone you are editing. This will add a new vertex to that line to move around.
|
||||

|
||||
- Add additional Zones as you like, Zones can be separated but also overlapping (See [Limitations]( ) for details)
|
||||
- After finishing the zone setup, click the "Store in EEPROM" Button to save the zones on the Flight Controller. It is important that the FC reboots after storing, as the Zones can only be used after a fresh boot process.
|
||||

|
||||
|
||||
## Global Settings
|
||||
- In the Advanced Tuning Panel, you will find additional global settings for Geozones
|
||||

|
||||
- Detection Distance `geozone_detection_distance`: Defines at what distance a Geozone will be shown as a System Message if a breach is imminent.
|
||||
- Avoid Altitude Range `geozone_avoid_altitude_range`: When the Aircraft approaches an NFZ that has a upper limit (can be overflown at higher altitude), INAV will climb above the Zone automatically if the altitude difference between Zone ceiling and current Aircraft altitude is less, than this value. For fixed wing, you need to consider how steep the possible climb angle is.
|
||||
- Safe Altitude Distance `geozone_safe_altitude_distance`: Vertical safety margin to avoid a ceiling or floor altitude breach at high vertical speed. If your FZ Ceiling is at 100m and this value set to 10m, the aircraft will not allow you to fly above 90m and descents if the Aircraft overshoots.
|
||||
- Safehome as Inclusive `geozone_safehome_as_inclusive`: Defines every Safehome location as a circular Inclusive zone with the radius of `safehome_max_distance` to allow a FZ at ground altitude (For Landings) if the general FZ around it might have a minimum altitude.
|
||||
- Safehome Zone Action `geozone_safehome_zone_action`: Defines the action on zone breach if Safehome is enabled as inclusive. This is helpful for flying fields with distance or altitude restrictions for LOS Pilots.
|
||||
- Multirotor Stop Distance `geozone_mr_stop_distance:`: Distance from the Border a Multirotor will stop, if the Fence Action is Avoid or Loiter (For fixed wings, this will be calculated from the Loiter-Radius of the Plane).
|
||||
- No Way Home Action `geozone_no_way_home_action`: If RTH cannot find a possible route in FS or RTH modes, the Aircraft will either emergency land or fly straight back home and ignores NFZ.
|
||||
|
||||
## Functions and Behaviors
|
||||
- Zone Type: Inclusive
|
||||
- If craft is armed inside the Inclusive FZ, everything outside that zone is considered an NFZ.
|
||||
- Inclusive FZ can be combined if they overlap and will be handled as one zone.
|
||||
- Overlapping multiple FZ allows different upper and lower altitude limits for each zone, as long as they still overlap in 3D Space (Both overlapping zones have to have a overlapping altitude range as well).
|
||||
- Arming the aircraft outside of an Inclusive Zone is prohibited within a 2km distance to the next vertex (Distance to a border between two vertex is not checked). Arming override can be used. Arming at a distance bigger than 2km is possible.
|
||||
- Arming a craft outside of an Inclusive FZ will disable all Inclusive zones.
|
||||
- Zone Type: Exclusive
|
||||
- Arming inside an Exclusive NFZ is prohibited. Arming override can be used but not recommended. If armed inside an NFZ the Pilot keeps control until the NFZ is left, then any configured Action will be executed on re-enter.
|
||||
- Exclusive Zones can be combined and overlapped as needed.
|
||||
- Exclusive NFZ with an upper or lower limit other than 0 can be overflown and underflown. The Automatic avoidance will only fly above NFZ if possible and never below.
|
||||
- Actions:
|
||||
- Avoid: Also called “Bounce” (only airplanes): The aircraft flies away from the boundary at the same angle it approached it, like a pool ball bouncing off the table border. Multirotor will switch into "Position Hold".
|
||||
- Hold: Position in front of the boundary is held. Airplances will adjust their loiter center according to the loider radius, to stay away from the border while circling.
|
||||
- RTH: Triggers Return To Home. The Failsafe RTH Procedure is executed, so RTH Trackback is also used if enabled for Failsafe situations.
|
||||
- None: No action (only info in OSD).
|
||||
- RTH:
|
||||
- If RTH is enabled by Failsafe, User Command or Zone Action, INAV will calculate a path to the Home Location that automatically avoids NFZ and tries to stay inside the current FZ.
|
||||
- If no Path can be calculated (Not able to climb over a blocking NFZ, No Intersection between FZ, too tight gaps between blocking NFZ) a configurable alternative action will be executed.
|
||||
- Direct RTH: Ignores Flight zones and comes back in a direct path.
|
||||
- Emergency Land: Executes a GPS enabled Emergency Landing (Circle down with horizontal position hold active on Planes).
|
||||
- When direct "Line of sight" with the Home location is reached (No zones blocking path), regular RTH settings are executed.
|
||||
- To abort the Smart-RTH feature and come back on a direct way, disable and Re-Enable RTH within 1 Second. This temporarily ignores all FZ and NFZ borders.
|
||||
- Return to Zone:
|
||||
- If the Aircraft breaches into an NFZ or out of a FZ (by avoiding tight angled Zones or flown in Acro mode and then the mode switches to any Self-Level mode), RTZ is initiated and the aircraft flies back into the last permitted zone on the shortest possible course.
|
||||
|
||||
## OSD Elements
|
||||
- Three dedicated OSD Elements have been added:
|
||||
- Fence-Distance Horizontal shows the distance to the nearest Fence Border and the heading to that border. (ID 145)
|
||||
- Fence-Distance Vertical shows the distance to the nearest ceiling or floor of a zone. (ID 146)
|
||||
- Fence-Direction Vertical is an optional element to show if the nearest vertical border is above or below the aircraft. (ID 144)
|
||||

|
||||
- The Flight-Mode will show AUTO if the Aircraft executes any kind of Fence-Action.
|
||||
- The System-Message shows the distance to a potential fence breach point, based on the current aircraft Attitude and Heading.
|
||||
- Additionally, the System Message shows the current Fence Action that is Executed.
|
||||
|
||||
|
||||
## Limitations
|
||||
- The maximum number of dedicated zones of any type is 63.
|
||||
- The maximum number of vertices of all zones combined is 127. Every circular zone uses 2 vertices while every polygon has to consist of at least 3 vertices.
|
||||
- INAV can only execute one border-breach action at a time. This is especially important to consider for Airplanes that cannot hover.
|
||||
- Complicated Zone setups with overlaps and tight areas can cause a loiter or "bounce" into another NFZ that was not considered before.
|
||||
- This can lead to a "Return to FZ" action that tries to find the shortest path into an allowed area.
|
||||
- All Geozone Actions are disabled when in Waypoint Mode. The Pilot is responsible for planning his mission accordingly, to not create a path that crosses NFZ areas. If a mission leads to such an area and the pilot disables WP mode, a "Return to FZ" action will be executed.
|
||||
- All Geozone Actions are disabled in ACRO and MANUAL Mode. INAV will not take over control in these modes and only OSD Warnings are shown.
|
||||
- Planning the Geozone as a polygon, needs to have the vertex numbering to be counter clockwise in ascending order. One vertex must not be dragged over another border to create crossing borders within one zone. INAV Configurator and MWP will check for that before uploading.
|
||||
- Examples of Zones that are not allowed:
|
||||

|
||||
- To properly combine multiple Inclusion FZ into one area, the Zones need to overlap at 2 borders and the points where the borders touch, must be at least 2.5x Loiter-Radius apart from Airplanes at least 2.5x Multirotor Stop Distance apart for Multirotor.
|
||||
- Example:
|
||||

|
||||
- If multiple zones with different minimum and maximum altitudes are combined, they need to vertically overlap at least 50m.
|
||||
- There is a chance that Smart RTH cannot find a path around NFZ areas, if there are multiple very big zones blocking the path. Due to hardware limitations, the amount of waypoints that Smart RTH can create are limited. Many Zones with very long border lines (>500m) cause additional waypoints.
|
||||
- It is not recommended to edit geozones in CLI by hand as this bypasses a lot of sanity checks. Potential errors in zones will disable them or can lead to unexpected behaviors. Transferring Geozones with a DIFF between aircraft is fine.
|
||||
|
||||
## CLI
|
||||
The Geozone Information are stored in two separate data arrays. The first array holds the main Geozone Information and settings. The second array holds the Geozone vertices.
|
||||
The following commands are available for users:
|
||||
|
||||
- `geozone` without argument lists the current settings
|
||||
- `geozone reset <id>` resets a specific geozone and all related vertices. If no ID proveded, all geozones and vertices will be deleted.
|
||||
- `geozone vertex` - lists all vertices.
|
||||
- `geozone vertex reset` - deletes all vertices.
|
||||
- `geozone vertex reset <zone id>` - Deletes all vertices of the zone.
|
||||
- `geozone vertex reset <zone id> <vertex id>` - Deletes the vertex with the corresponding id from a zone.
|
||||
|
||||
The following information are for app-developers. _DO NOT EDIT GEOZONES MANUALLY CLI_!
|
||||
|
||||
`geozone <id> <shape> <type> <minimum altitude> <maximum altitude> <is_amsl> <fence action> <vertices count>`
|
||||
|
||||
- id: 0 - 63
|
||||
- shape: 0 = Circular, 1 = Polygonal
|
||||
- type: 0 = Exclusive, 1 = Inclusive
|
||||
- minimum altitude: In centimetres, 0 = ground
|
||||
- maximum altitude: In centimetres, 0 = infinity
|
||||
- is_amsl: 0 = relative, 1 = AMSL
|
||||
- fence action: 0 = None, 1 = Avoid, 2 = Position hold, 3 = Return To Home
|
||||
- vertices count: 0-126 - Sanity check if number of vertices matches with configured zones
|
||||
|
||||
`geozone vertex <zone id> <vertex idx> <latitude> <logitude>`
|
||||
|
||||
- zone id: (0-63) The zone id to which this vertex belongs
|
||||
- vertex idx: Index of the vertex (0-126)
|
||||
- latitude/ logitude: Longitude and latitude of the vertex. Values in decimal degrees * 1e7. Example:the value 47.562004o becomes 475620040
|
||||
|
||||
|
|
@ -70,7 +70,7 @@ Now, there are two ways to [configure CF](Configuration.md); via the Configurat
|
|||
* Verify the range of each channel goes from ~1000 to ~2000. See also [controls](Controls.md). and `rx_min_usec` and `rx_max_usec`.
|
||||
* You can also set EXPO here instead of your Tx.
|
||||
* Click Save!
|
||||
* Modes tab: Setup the desired modes. See the [modes](Modes.md) chapter for what each mode does, but for the beginning you mainly need HORIZON, if any.
|
||||
* Modes tab: Setup the desired modes. See the [Modes in the wiki](https://github.com/iNavFlight/inav/wiki/Modes) for what each mode does.
|
||||
|
||||
* Before finishing this section, you should calibrate the ESCs, install the FC to the frame, and connect the RSSI cable, buzzer and battery if you have chosen to use those.
|
||||
|
||||
|
|
|
@ -41,6 +41,8 @@ The default `mmix` throttle value is 0.0, It will not show in `diff` command whe
|
|||
- -1.0<throttle<=0.0 : motor stop, default value 0, set to -1 to use a place holder for subsequent motor rules
|
||||
- -2.0<throttle<-1.0 : spin regardless of throttle position at speed `abs(throttle)-1` when Mixer Transition is activated.
|
||||
|
||||
Airmode type should be set to "STICK_CENTER". Airmode type must NOT be set to "THROTTLE_THRESHOLD". If set to throttle threshold the (-) motor will spin till throttle threshold is passed.
|
||||
|
||||
Example: This will spin motor number 5 (counting from 1) at 20%, in transition mode only, to gain speed for a "4 rotor 1 pusher" setup:
|
||||
|
||||
```
|
||||
|
|
|
@ -5,13 +5,13 @@ The navigation system in INAV is responsible for assisting the pilot allowing al
|
|||
## NAV ALTHOLD mode - altitude hold
|
||||
|
||||
Altitude hold requires a valid source of altitude - barometer, GPS or rangefinder. The best source is chosen automatically.
|
||||
In this mode THROTTLE stick controls climb rate (vertical velocity). When pilot moves stick up - quad goes up, pilot moves stick down - quad descends, you keep stick at neutral position - quad hovers.
|
||||
In this mode THROTTLE stick controls climb rate (vertical velocity). When pilot moves stick up - aircraft goes up, pilot moves stick down -
|
||||
aircraft descends, you keep stick at neutral position - aircraft maintains current altitude.
|
||||
|
||||
By default, GPS is available as an altitude source for airplanes only. Multirotor requires barometer, unless *inav_use_gps_no_baro* is enabled.
|
||||
|
||||
### CLI parameters affecting ALTHOLD mode:
|
||||
* *nav_use_midthr_for_althold* - when set to "0", firmware will remember where your throttle stick was when ALTHOLD was activated - this will be considered neutral position. When set to "1" - 50% throttle will be considered neutral position.
|
||||
* *inav_use_gps_no_baro* - Multirotor only: enable althold based on GPS only, without baromemer installed. Default is OFF.
|
||||
|
||||
|
||||
### Related PIDs
|
||||
PIDs affecting altitude hold: ALT & VEL
|
||||
|
@ -25,12 +25,12 @@ Throttle tilt compensation attempts to maintain constant vertical thrust when co
|
|||
|
||||
## NAV POSHOLD mode - position hold
|
||||
|
||||
Position hold requires GPS, accelerometer and compass sensors. Multirotor requires barometer, unless *inav_use_gps_no_baro* is enabled. Flight modes that require a compass (POSHOLD, RTH) are locked until compass is properly calibrated.
|
||||
Position hold requires GPS, accelerometer and compass sensors. Multirotor requires barometer, unless is enabled. Flight modes that require a compass (POSHOLD, RTH) are locked until compass is properly calibrated.
|
||||
When activated, this mode will attempt to keep copter where it is (based on GPS coordinates). From INAV 2.0, POSHOLD is a full 3D position hold. Heading hold in this mode is assumed and activated automatically.
|
||||
|
||||
### CLI parameters affecting POSHOLD mode:
|
||||
* *nav_user_control_mode* - can be set to "0" (GPS_ATTI) or "1" (GPS_CRUISE), controls how firmware will respond to roll/pitch stick movement. When in GPS_ATTI mode, right stick controls attitude, when it is released, new position is recorded and held. When in GPS_CRUISE mode right stick controls velocity and firmware calculates required attitude on its own.
|
||||
* *inav_use_gps_no_baro* - Multirotor only: enable althold based on GPS only, without baromemer installed. Default is OFF.
|
||||
|
||||
|
||||
### Related PIDs
|
||||
PIDs affecting position hold: POS, POSR
|
||||
|
@ -42,7 +42,7 @@ PID meaning:
|
|||
|
||||
Home for RTH is the position where vehicle was first armed. This position may be offset by the CLI settings `nav_rth_home_offset_distance` and `nav_rth_home_offset_direction`. This position may also be overridden with Safehomes. RTH requires accelerometer, compass and GPS sensors.
|
||||
|
||||
RTH requires barometer for multirotor, unless unless *inav_use_gps_no_baro* is enabled.
|
||||
RTH requires barometer for multirotor.
|
||||
|
||||
RTH will maintain altitude during the return. When home is reached, a copter will attempt automated landing. An airplane will either loiter around the home position, or attempt an automated landing, depending on your settings.
|
||||
When deciding what altitude to maintain, RTH has 6 different modes of operation (controlled by *nav_rth_alt_mode* and *nav_rth_altitude* cli variables):
|
||||
|
|
359
docs/OSD.md
359
docs/OSD.md
|
@ -2,6 +2,15 @@
|
|||
|
||||
The On Screen Display, or OSD, is a feature that overlays flight data over the video image. This can be done on the flight controller, using the analogue MAX7456 chip. Digital systems take the OSD data, via MSP DisplayPort, send it to the video receiver; which combines the data with the image. You can specify what elements are displayed, and their locations on the image. Most systems are character based, and use the MAX7456 analogue setup, or MSP DisplayPort. However, there are some different systems which are also supported. Such as the canvas based FrSKY PixelOSD on analogue. Canvas OSDs draw shapes on the image. Whereas character based OSDs use font characters to display the data.
|
||||
|
||||
|
||||
General OSD information is in this document. Other documents cover specific OSD-related topics:
|
||||
* [Custom OSD Messages](https://github.com/iNavFlight/inav/wiki/OSD-custom-messages)
|
||||
* [OSD Hud and ESP32 radars](https://github.com/iNavFlight/inav/wiki/OSD-Hud-and-ESP32-radars)
|
||||
* [OSD Joystick](https://github.com/iNavFlight/inav/blob/master/docs/OSD%20Joystick.md)
|
||||
* [DJI compatible OSD.md](https://github.com/iNavFlight/inav/blob/master/docs/DJI%20compatible%20OSD.md)
|
||||
* [Pixel OSD FAQ](https://github.com/iNavFlight/inav/wiki/Pixel-OSD-FAQs)
|
||||
|
||||
|
||||
## Features and Limitations
|
||||
Not all OSDs are created equally. This table shows the differences between the different systems available.
|
||||
|
||||
|
@ -19,155 +28,167 @@ Not all OSDs are created equally. This table shows the differences between the d
|
|||
## OSD Elements
|
||||
Here are the OSD Elements provided by INAV.
|
||||
|
||||
| ID | Element | Added |
|
||||
|-----|--------------------------------------------------|--------|
|
||||
| 0 | OSD_RSSI_VALUE | 1.0.0 |
|
||||
| 1 | OSD_MAIN_BATT_VOLTAGE | 1.0.0 |
|
||||
| 2 | OSD_CROSSHAIRS | 1.0.0 |
|
||||
| 3 | OSD_ARTIFICIAL_HORIZON | 1.0.0 |
|
||||
| 4 | OSD_HORIZON_SIDEBARS | 1.0.0 |
|
||||
| 5 | OSD_ONTIME | 1.0.0 |
|
||||
| 6 | OSD_FLYTIME | 1.0.0 |
|
||||
| 7 | OSD_FLYMODE | 1.0.0 |
|
||||
| 8 | OSD_CRAFT_NAME | 1.0.0 |
|
||||
| 9 | OSD_THROTTLE_POS | 1.0.0 |
|
||||
| 10 | OSD_VTX_CHANNEL | 1.0.0 |
|
||||
| 11 | OSD_CURRENT_DRAW | 1.0.0 |
|
||||
| 12 | OSD_MAH_DRAWN | 1.0.0 |
|
||||
| 13 | OSD_GPS_SPEED | 1.0.0 |
|
||||
| 14 | OSD_GPS_SATS | 1.0.0 |
|
||||
| 15 | OSD_ALTITUDE | 1.0.0 |
|
||||
| 16 | OSD_ROLL_PIDS | 1.6.0 |
|
||||
| 17 | OSD_PITCH_PIDS | 1.6.0 |
|
||||
| 18 | OSD_YAW_PIDS | 1.6.0 |
|
||||
| 19 | OSD_POWER | 1.6.0 |
|
||||
| 20 | OSD_GPS_LON | 1.6.0 |
|
||||
| 21 | OSD_GPS_LAT | 1.6.0 |
|
||||
| 22 | OSD_HOME_DIR | 1.6.0 |
|
||||
| 23 | OSD_HOME_DIST | 1.6.0 |
|
||||
| 24 | OSD_HEADING | 1.6.0 |
|
||||
| 25 | OSD_VARIO | 1.6.0 |
|
||||
| 26 | OSD_VARIO_NUM | 1.6.0 |
|
||||
| 27 | OSD_AIR_SPEED | 1.7.3 |
|
||||
| 28 | OSD_ONTIME_FLYTIME | 1.8.0 |
|
||||
| 29 | OSD_RTC_TIME | 1.8.0 |
|
||||
| 30 | OSD_MESSAGES | 1.8.0 |
|
||||
| 31 | OSD_GPS_HDOP | 1.8.0 |
|
||||
| 32 | OSD_MAIN_BATT_CELL_VOLTAGE | 1.8.0 |
|
||||
| 33 | OSD_SCALED_THROTTLE_POS | 1.8.0 |
|
||||
| 34 | OSD_HEADING_GRAPH | 1.8.0 |
|
||||
| 35 | OSD_EFFICIENCY_MAH_PER_KM | 1.9.0 |
|
||||
| 36 | OSD_WH_DRAWN | 1.9.0 |
|
||||
| 37 | OSD_BATTERY_REMAINING_CAPACITY | 1.9.0 |
|
||||
| 38 | OSD_BATTERY_REMAINING_PERCENT | 1.9.0 |
|
||||
| 39 | OSD_EFFICIENCY_WH_PER_KM | 1.9.0 |
|
||||
| 40 | OSD_TRIP_DIST | 1.9.1 |
|
||||
| 41 | OSD_ATTITUDE_PITCH | 2.0.0 |
|
||||
| 42 | OSD_ATTITUDE_ROLL | 2.0.0 |
|
||||
| 43 | OSD_MAP_NORTH | 2.0.0 |
|
||||
| 44 | OSD_MAP_TAKEOFF | 2.0.0 |
|
||||
| 45 | OSD_RADAR | 2.0.0 |
|
||||
| 46 | OSD_WIND_SPEED_HORIZONTAL | 2.0.0 |
|
||||
| 47 | OSD_WIND_SPEED_VERTICAL | 2.0.0 |
|
||||
| 48 | OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH | 2.0.0 |
|
||||
| 49 | OSD_REMAINING_DISTANCE_BEFORE_RTH | 2.0.0 |
|
||||
| 50 | OSD_HOME_HEADING_ERROR | 2.0.0 |
|
||||
| 51 | OSD_COURSE_HOLD_ERROR | 2.0.0 |
|
||||
| 52 | OSD_COURSE_HOLD_ADJUSTMENT | 2.0.0 |
|
||||
| 53 | OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE | 2.0.0 |
|
||||
| 54 | OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE | 2.0.0 |
|
||||
| 55 | OSD_POWER_SUPPLY_IMPEDANCE | 2.0.0 |
|
||||
| 56 | OSD_LEVEL_PIDS | 2.0.0 |
|
||||
| 57 | OSD_POS_XY_PIDS | 2.0.0 |
|
||||
| 58 | OSD_POS_Z_PIDS | 2.0.0 |
|
||||
| 59 | OSD_VEL_XY_PIDS | 2.0.0 |
|
||||
| 60 | OSD_VEL_Z_PIDS | 2.0.0 |
|
||||
| 61 | OSD_HEADING_P | 2.0.0 |
|
||||
| 62 | OSD_BOARD_ALIGN_ROLL | 2.0.0 |
|
||||
| 63 | OSD_BOARD_ALIGN_PITCH | 2.0.0 |
|
||||
| 64 | OSD_RC_EXPO | 2.0.0 |
|
||||
| 65 | OSD_RC_YAW_EXPO | 2.0.0 |
|
||||
| 66 | OSD_THROTTLE_EXPO | 2.0.0 |
|
||||
| 67 | OSD_PITCH_RATE | 2.0.0 |
|
||||
| 68 | OSD_ROLL_RATE | 2.0.0 |
|
||||
| 69 | OSD_YAW_RATE | 2.0.0 |
|
||||
| 70 | OSD_MANUAL_RC_EXPO | 2.0.0 |
|
||||
| 71 | OSD_MANUAL_RC_YAW_EXPO | 2.0.0 |
|
||||
| 72 | OSD_MANUAL_PITCH_RATE | 2.0.0 |
|
||||
| 73 | OSD_MANUAL_ROLL_RATE | 2.0.0 |
|
||||
| 74 | OSD_MANUAL_YAW_RATE | 2.0.0 |
|
||||
| 75 | OSD_NAV_FW_CRUISE_THR | 2.0.0 |
|
||||
| 76 | OSD_NAV_FW_PITCH2THR | 2.0.0 |
|
||||
| 77 | OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE | 2.0.0 |
|
||||
| 78 | OSD_DEBUG | 2.0.0 |
|
||||
| 79 | OSD_FW_ALT_PID_OUTPUTS | 2.0.0 |
|
||||
| 80 | OSD_FW_POS_PID_OUTPUTS | 2.0.0 |
|
||||
| 81 | OSD_MC_VEL_X_PID_OUTPUTS | 2.0.0 |
|
||||
| 82 | OSD_MC_VEL_Y_PID_OUTPUTS | 2.0.0 |
|
||||
| 83 | OSD_MC_VEL_Z_PID_OUTPUTS | 2.0.0 |
|
||||
| 84 | OSD_MC_POS_XYZ_P_OUTPUTS | 2.0.0 |
|
||||
| 85 | OSD_3D_SPEED | 2.1.0 |
|
||||
| 86 | OSD_IMU_TEMPERATURE | 2.1.0 |
|
||||
| 87 | OSD_BARO_TEMPERATURE | 2.1.0 |
|
||||
| 88 | OSD_TEMP_SENSOR_0_TEMPERATURE | 2.1.0 |
|
||||
| 89 | OSD_TEMP_SENSOR_1_TEMPERATURE | 2.1.0 |
|
||||
| 90 | OSD_TEMP_SENSOR_2_TEMPERATURE | 2.1.0 |
|
||||
| 91 | OSD_TEMP_SENSOR_3_TEMPERATURE | 2.1.0 |
|
||||
| 92 | OSD_TEMP_SENSOR_4_TEMPERATURE | 2.1.0 |
|
||||
| 93 | OSD_TEMP_SENSOR_5_TEMPERATURE | 2.1.0 |
|
||||
| 94 | OSD_TEMP_SENSOR_6_TEMPERATURE | 2.1.0 |
|
||||
| 95 | OSD_TEMP_SENSOR_7_TEMPERATURE | 2.1.0 |
|
||||
| 96 | OSD_ALTITUDE_MSL | 2.1.0 |
|
||||
| 97 | OSD_PLUS_CODE | 2.1.0 |
|
||||
| 98 | OSD_MAP_SCALE | 2.2.0 |
|
||||
| 99 | OSD_MAP_REFERENCE | 2.2.0 |
|
||||
| 100 | OSD_GFORCE | 2.2.0 |
|
||||
| 101 | OSD_GFORCE_X | 2.2.0 |
|
||||
| 102 | OSD_GFORCE_Y | 2.2.0 |
|
||||
| 103 | OSD_GFORCE_Z | 2.2.0 |
|
||||
| 104 | OSD_RC_SOURCE | 2.2.0 |
|
||||
| 105 | OSD_VTX_POWER | 2.2.0 |
|
||||
| 106 | OSD_ESC_RPM | 2.3.0 |
|
||||
| 107 | OSD_ESC_TEMPERATURE | 2.5.0 |
|
||||
| 108 | OSD_AZIMUTH | 2.6.0 |
|
||||
| 109 | OSD_CRSF_RSSI_DBM | 2.6.0 |
|
||||
| 110 | OSD_CRSF_LQ | 2.6.0 |
|
||||
| 111 | OSD_CRSF_SNR_DB | 2.6.0 |
|
||||
| 112 | OSD_CRSF_TX_POWER | 2.6.0 |
|
||||
| 113 | OSD_GVAR_0 | 2.6.0 |
|
||||
| 114 | OSD_GVAR_1 | 2.6.0 |
|
||||
| 115 | OSD_GVAR_2 | 2.6.0 |
|
||||
| 116 | OSD_GVAR_3 | 2.6.0 |
|
||||
| 117 | OSD_TPA | 2.6.0 |
|
||||
| 118 | OSD_NAV_FW_CONTROL_SMOOTHNESS | 2.6.0 |
|
||||
| 119 | OSD_VERSION | 3.0.0 |
|
||||
| 120 | OSD_RANGEFINDER | 3.0.0 |
|
||||
| 121 | OSD_PLIMIT_REMAINING_BURST_TIME | 3.0.0 |
|
||||
| 122 | OSD_PLIMIT_ACTIVE_CURRENT_LIMIT | 3.0.0 |
|
||||
| 123 | OSD_PLIMIT_ACTIVE_POWER_LIMIT | 3.0.0 |
|
||||
| 124 | OSD_GLIDESLOPE | 3.0.1 |
|
||||
| 125 | OSD_GPS_MAX_SPEED | 4.0.0 |
|
||||
| 126 | OSD_3D_MAX_SPEED | 4.0.0 |
|
||||
| 127 | OSD_AIR_MAX_SPEED | 4.0.0 |
|
||||
| 128 | OSD_ACTIVE_PROFILE | 4.0.0 |
|
||||
| 129 | OSD_MISSION | 4.0.0 |
|
||||
| 130 | OSD_SWITCH_INDICATOR_0 | 5.0.0 |
|
||||
| 131 | OSD_SWITCH_INDICATOR_1 | 5.0.0 |
|
||||
| 132 | OSD_SWITCH_INDICATOR_2 | 5.0.0 |
|
||||
| 133 | OSD_SWITCH_INDICATOR_3 | 5.0.0 |
|
||||
| 134 | OSD_TPA_TIME_CONSTANT | 5.0.0 |
|
||||
| 135 | OSD_FW_LEVEL_TRIM | 5.0.0 |
|
||||
| 136 | OSD_GLIDE_TIME_REMAINING | 6.0.0 |
|
||||
| 137 | OSD_GLIDE_RANGE | 6.0.0 |
|
||||
| 138 | OSD_CLIMB_EFFICIENCY | 6.0.0 |
|
||||
| 139 | OSD_NAV_WP_MULTI_MISSION_INDEX | 6.0.0 |
|
||||
| 140 | OSD_GROUND_COURSE | 6.0.0 |
|
||||
| 141 | OSD_CROSS_TRACK_ERROR | 6.0.0 |
|
||||
| 142 | OSD_PILOT_NAME | 6.0.0 |
|
||||
| 143 | OSD_PAN_SERVO_CENTRED | 6.0.0 |
|
||||
| 144 | OSD_MULTI_FUNCTION | 7.0.0 |
|
||||
| 145 | OSD_ODOMETER | 7.0.0 |
|
||||
| 146 | OSD_PILOT_LOGO | 7.0.0 |
|
||||
| ID | Element | Added | Notes |
|
||||
|-----|--------------------------------------------------|--------|-------|
|
||||
| 0 | OSD_RSSI_VALUE | 1.0.0 | |
|
||||
| 1 | OSD_MAIN_BATT_VOLTAGE | 1.0.0 | |
|
||||
| 2 | OSD_CROSSHAIRS | 1.0.0 | |
|
||||
| 3 | OSD_ARTIFICIAL_HORIZON | 1.0.0 | |
|
||||
| 4 | OSD_HORIZON_SIDEBARS | 1.0.0 | |
|
||||
| 5 | OSD_ONTIME | 1.0.0 | |
|
||||
| 6 | OSD_FLYTIME | 1.0.0 | |
|
||||
| 7 | OSD_FLYMODE | 1.0.0 | |
|
||||
| 8 | OSD_CRAFT_NAME | 1.0.0 | |
|
||||
| 9 | OSD_THROTTLE_POS | 1.0.0 | |
|
||||
| 10 | OSD_VTX_CHANNEL | 1.0.0 | |
|
||||
| 11 | OSD_CURRENT_DRAW | 1.0.0 | |
|
||||
| 12 | OSD_MAH_DRAWN | 1.0.0 | |
|
||||
| 13 | OSD_GPS_SPEED | 1.0.0 | |
|
||||
| 14 | OSD_GPS_SATS | 1.0.0 | |
|
||||
| 15 | OSD_ALTITUDE | 1.0.0 | |
|
||||
| 16 | OSD_ROLL_PIDS | 1.6.0 | |
|
||||
| 17 | OSD_PITCH_PIDS | 1.6.0 | |
|
||||
| 18 | OSD_YAW_PIDS | 1.6.0 | |
|
||||
| 19 | OSD_POWER | 1.6.0 | |
|
||||
| 20 | OSD_GPS_LON | 1.6.0 | |
|
||||
| 21 | OSD_GPS_LAT | 1.6.0 | |
|
||||
| 22 | OSD_HOME_DIR | 1.6.0 | |
|
||||
| 23 | OSD_HOME_DIST | 1.6.0 | |
|
||||
| 24 | OSD_HEADING | 1.6.0 | |
|
||||
| 25 | OSD_VARIO | 1.6.0 | |
|
||||
| 26 | OSD_VARIO_NUM | 1.6.0 | |
|
||||
| 27 | OSD_AIR_SPEED | 1.7.3 | |
|
||||
| 28 | OSD_ONTIME_FLYTIME | 1.8.0 | |
|
||||
| 29 | OSD_RTC_TIME | 1.8.0 | |
|
||||
| 30 | OSD_MESSAGES | 1.8.0 | |
|
||||
| 31 | OSD_GPS_HDOP | 1.8.0 | |
|
||||
| 32 | OSD_MAIN_BATT_CELL_VOLTAGE | 1.8.0 | |
|
||||
| 33 | OSD_SCALED_THROTTLE_POS | 1.8.0 | |
|
||||
| 34 | OSD_HEADING_GRAPH | 1.8.0 | |
|
||||
| 35 | OSD_EFFICIENCY_MAH_PER_KM | 1.9.0 | |
|
||||
| 36 | OSD_WH_DRAWN | 1.9.0 | |
|
||||
| 37 | OSD_BATTERY_REMAINING_CAPACITY | 1.9.0 | |
|
||||
| 38 | OSD_BATTERY_REMAINING_PERCENT | 1.9.0 | |
|
||||
| 39 | OSD_EFFICIENCY_WH_PER_KM | 1.9.0 | |
|
||||
| 40 | OSD_TRIP_DIST | 1.9.1 | |
|
||||
| 41 | OSD_ATTITUDE_PITCH | 2.0.0 | |
|
||||
| 42 | OSD_ATTITUDE_ROLL | 2.0.0 | |
|
||||
| 43 | OSD_MAP_NORTH | 2.0.0 | |
|
||||
| 44 | OSD_MAP_TAKEOFF | 2.0.0 | |
|
||||
| 45 | OSD_RADAR | 2.0.0 | |
|
||||
| 46 | OSD_WIND_SPEED_HORIZONTAL | 2.0.0 | |
|
||||
| 47 | OSD_WIND_SPEED_VERTICAL | 2.0.0 | |
|
||||
| 48 | OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH | 2.0.0 | |
|
||||
| 49 | OSD_REMAINING_DISTANCE_BEFORE_RTH | 2.0.0 | |
|
||||
| 50 | OSD_HOME_HEADING_ERROR | 2.0.0 | |
|
||||
| 51 | OSD_COURSE_HOLD_ERROR | 2.0.0 | |
|
||||
| 52 | OSD_COURSE_HOLD_ADJUSTMENT | 2.0.0 | |
|
||||
| 53 | OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE | 2.0.0 | |
|
||||
| 54 | OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE | 2.0.0 | |
|
||||
| 55 | OSD_POWER_SUPPLY_IMPEDANCE | 2.0.0 | |
|
||||
| 56 | OSD_LEVEL_PIDS | 2.0.0 | |
|
||||
| 57 | OSD_POS_XY_PIDS | 2.0.0 | |
|
||||
| 58 | OSD_POS_Z_PIDS | 2.0.0 | |
|
||||
| 59 | OSD_VEL_XY_PIDS | 2.0.0 | |
|
||||
| 60 | OSD_VEL_Z_PIDS | 2.0.0 | |
|
||||
| 61 | OSD_HEADING_P | 2.0.0 | |
|
||||
| 62 | OSD_BOARD_ALIGN_ROLL | 2.0.0 | |
|
||||
| 63 | OSD_BOARD_ALIGN_PITCH | 2.0.0 | |
|
||||
| 64 | OSD_RC_EXPO | 2.0.0 | |
|
||||
| 65 | OSD_RC_YAW_EXPO | 2.0.0 | |
|
||||
| 66 | OSD_THROTTLE_EXPO | 2.0.0 | |
|
||||
| 67 | OSD_PITCH_RATE | 2.0.0 | |
|
||||
| 68 | OSD_ROLL_RATE | 2.0.0 | |
|
||||
| 69 | OSD_YAW_RATE | 2.0.0 | |
|
||||
| 70 | OSD_MANUAL_RC_EXPO | 2.0.0 | |
|
||||
| 71 | OSD_MANUAL_RC_YAW_EXPO | 2.0.0 | |
|
||||
| 72 | OSD_MANUAL_PITCH_RATE | 2.0.0 | |
|
||||
| 73 | OSD_MANUAL_ROLL_RATE | 2.0.0 | |
|
||||
| 74 | OSD_MANUAL_YAW_RATE | 2.0.0 | |
|
||||
| 75 | OSD_NAV_FW_CRUISE_THR | 2.0.0 | |
|
||||
| 76 | OSD_NAV_FW_PITCH2THR | 2.0.0 | |
|
||||
| 77 | OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE | 2.0.0 | |
|
||||
| 78 | OSD_DEBUG | 2.0.0 | |
|
||||
| 79 | OSD_FW_ALT_PID_OUTPUTS | 2.0.0 | |
|
||||
| 80 | OSD_FW_POS_PID_OUTPUTS | 2.0.0 | |
|
||||
| 81 | OSD_MC_VEL_X_PID_OUTPUTS | 2.0.0 | |
|
||||
| 82 | OSD_MC_VEL_Y_PID_OUTPUTS | 2.0.0 | |
|
||||
| 83 | OSD_MC_VEL_Z_PID_OUTPUTS | 2.0.0 | |
|
||||
| 84 | OSD_MC_POS_XYZ_P_OUTPUTS | 2.0.0 | |
|
||||
| 85 | OSD_3D_SPEED | 2.1.0 | |
|
||||
| 86 | OSD_IMU_TEMPERATURE | 2.1.0 | |
|
||||
| 87 | OSD_BARO_TEMPERATURE | 2.1.0 | |
|
||||
| 88 | OSD_TEMP_SENSOR_0_TEMPERATURE | 2.1.0 | |
|
||||
| 89 | OSD_TEMP_SENSOR_1_TEMPERATURE | 2.1.0 | |
|
||||
| 90 | OSD_TEMP_SENSOR_2_TEMPERATURE | 2.1.0 | |
|
||||
| 91 | OSD_TEMP_SENSOR_3_TEMPERATURE | 2.1.0 | |
|
||||
| 92 | OSD_TEMP_SENSOR_4_TEMPERATURE | 2.1.0 | |
|
||||
| 93 | OSD_TEMP_SENSOR_5_TEMPERATURE | 2.1.0 | |
|
||||
| 94 | OSD_TEMP_SENSOR_6_TEMPERATURE | 2.1.0 | |
|
||||
| 95 | OSD_TEMP_SENSOR_7_TEMPERATURE | 2.1.0 | |
|
||||
| 96 | OSD_ALTITUDE_MSL | 2.1.0 | |
|
||||
| 97 | OSD_PLUS_CODE | 2.1.0 | |
|
||||
| 98 | OSD_MAP_SCALE | 2.2.0 | |
|
||||
| 99 | OSD_MAP_REFERENCE | 2.2.0 | |
|
||||
| 100 | OSD_GFORCE | 2.2.0 | |
|
||||
| 101 | OSD_GFORCE_X | 2.2.0 | |
|
||||
| 102 | OSD_GFORCE_Y | 2.2.0 | |
|
||||
| 103 | OSD_GFORCE_Z | 2.2.0 | |
|
||||
| 104 | OSD_RC_SOURCE | 2.2.0 | |
|
||||
| 105 | OSD_VTX_POWER | 2.2.0 | |
|
||||
| 106 | OSD_ESC_RPM | 2.3.0 | |
|
||||
| 107 | OSD_ESC_TEMPERATURE | 2.5.0 | |
|
||||
| 108 | OSD_AZIMUTH | 2.6.0 | |
|
||||
| 109 | OSD_CRSF_RSSI_DBM | 2.6.0 | |
|
||||
| 110 | OSD_CRSF_LQ | 2.6.0 | |
|
||||
| 111 | OSD_CRSF_SNR_DB | 2.6.0 | |
|
||||
| 112 | OSD_CRSF_TX_POWER | 2.6.0 | |
|
||||
| 113 | OSD_GVAR_0 | 2.6.0 | |
|
||||
| 114 | OSD_GVAR_1 | 2.6.0 | |
|
||||
| 115 | OSD_GVAR_2 | 2.6.0 | |
|
||||
| 116 | OSD_GVAR_3 | 2.6.0 | |
|
||||
| 117 | OSD_TPA | 2.6.0 | |
|
||||
| 118 | OSD_NAV_FW_CONTROL_SMOOTHNESS | 2.6.0 | |
|
||||
| 119 | OSD_VERSION | 3.0.0 | |
|
||||
| 120 | OSD_RANGEFINDER | 3.0.0 | |
|
||||
| 121 | OSD_PLIMIT_REMAINING_BURST_TIME | 3.0.0 | |
|
||||
| 122 | OSD_PLIMIT_ACTIVE_CURRENT_LIMIT | 3.0.0 | |
|
||||
| 123 | OSD_PLIMIT_ACTIVE_POWER_LIMIT | 3.0.0 | |
|
||||
| 124 | OSD_GLIDESLOPE | 3.0.1 | |
|
||||
| 125 | OSD_GPS_MAX_SPEED | 4.0.0 | |
|
||||
| 126 | OSD_3D_MAX_SPEED | 4.0.0 | |
|
||||
| 127 | OSD_AIR_MAX_SPEED | 4.0.0 | |
|
||||
| 128 | OSD_ACTIVE_PROFILE | 4.0.0 | |
|
||||
| 129 | OSD_MISSION | 4.0.0 | |
|
||||
| 130 | OSD_SWITCH_INDICATOR_0 | 5.0.0 | |
|
||||
| 131 | OSD_SWITCH_INDICATOR_1 | 5.0.0 | |
|
||||
| 132 | OSD_SWITCH_INDICATOR_2 | 5.0.0 | |
|
||||
| 133 | OSD_SWITCH_INDICATOR_3 | 5.0.0 | |
|
||||
| 134 | OSD_TPA_TIME_CONSTANT | 5.0.0 | |
|
||||
| 135 | OSD_FW_LEVEL_TRIM | 5.0.0 | |
|
||||
| 136 | OSD_GLIDE_TIME_REMAINING | 6.0.0 | |
|
||||
| 137 | OSD_GLIDE_RANGE | 6.0.0 | |
|
||||
| 138 | OSD_CLIMB_EFFICIENCY | 6.0.0 | |
|
||||
| 139 | OSD_NAV_WP_MULTI_MISSION_INDEX | 6.0.0 | |
|
||||
| 140 | OSD_GROUND_COURSE | 6.0.0 | |
|
||||
| 141 | OSD_CROSS_TRACK_ERROR | 6.0.0 | |
|
||||
| 142 | OSD_PILOT_NAME | 6.0.0 | |
|
||||
| 143 | OSD_PAN_SERVO_CENTRED | 6.0.0 | |
|
||||
| 144 | OSD_MULTI_FUNCTION | 7.0.0 | |
|
||||
| 145 | OSD_ODOMETER | 7.0.0 | For this to work correctly, stats must be enabled (`set stats=ON`). Otherwise, this will show the total flight distance. |
|
||||
| 146 | OSD_PILOT_LOGO | 7.0.0 | |
|
||||
| 147 | OSD_CUSTOM_ELEMENT_1 | 7.0.0 | |
|
||||
| 148 | OSD_CUSTOM_ELEMENT_2 | 7.0.0 | |
|
||||
| 149 | OSD_CUSTOM_ELEMENT_3 | 7.0.0 | |
|
||||
| 150 | OSD_ADSB_WARNING | 7.0.0 | |
|
||||
| 151 | OSD_ADSB_INFO | 7.0.0 | |
|
||||
| 152 | OSD_BLACKBOX | 8.0.0 | The element will be hidden unless blackbox recording is attempted. |
|
||||
| 153 | OSD_FORMATION_FLIGHT | 8.0.0 | |
|
||||
| 154 | OSD_CUSTOM_ELEMENT_4 | 8.0.0 | |
|
||||
| 155 | OSD_CUSTOM_ELEMENT_5 | 8.0.0 | |
|
||||
| 156 | OSD_CUSTOM_ELEMENT_6 | 8.0.0 | |
|
||||
| 157 | OSD_CUSTOM_ELEMENT_7 | 8.0.0 | |
|
||||
| 158 | OSD_CUSTOM_ELEMENT_8 | 8.0.0 | |
|
||||
|
||||
# Pilot Logos
|
||||
|
||||
|
@ -192,3 +213,43 @@ This is an example of the arming screen with the pilot logo enabled. This is usi
|
|||
|
||||
This is an example of setting the `osd_inav_to_pilot_logo_spacing` to 0. This will allow a larger, single logo.
|
||||

|
||||
|
||||
# Post Flight Statistics
|
||||
The post flight statistcs are set in the firmware. Statistics are only hidden if the supporting hardware is not present. Due to size contraints. The post flight statistics are spread over 2 pages on analogue systems.
|
||||
|
||||
## Statistics shown
|
||||
| Statistic | Requirement | Page | |
|
||||
|-------------------------------|-----------------------|-------|-|
|
||||
| Flight Time | | 1 | The total time from arm to disarm. |
|
||||
| Flight Distance | | 1 | |
|
||||
| Maximum Distance From Home | GPS | 1 | |
|
||||
| Maximum Speed | GPS | 1 | |
|
||||
| Average Speed | GPS | 1 | |
|
||||
| Maximum Altitude | Baro/GPS | 1 | |
|
||||
| Minimum Average Cell Voltage | | 1 | |
|
||||
| Minimum Pack Voltage | | 1 | |
|
||||
| Maximum Current | Current Sensor | 1 | |
|
||||
| Maximum Power | Current Sensor | 1 | |
|
||||
| Energy Used (Flight) | Current Sensor | 1 | |
|
||||
| Energy Used (Battery Total) | Current Sensor | 1 | This data is not reset on arming. |
|
||||
| Average Efficiency | Current Sensor & GPS | 1 | |
|
||||
| Minimum RSSI | | 2 | |
|
||||
| Minimum LQ | CRSF | 2 | |
|
||||
| Minmum dBm | CRSF | 2 | |
|
||||
| Minimum Satellites | GPS | 2 | |
|
||||
| Maximum Satellites | GPS | 2 | |
|
||||
| Minimum ESC Temperature | ESC Telemetry | 2 | |
|
||||
| Maximum ESC Temperature | ESC Telemetry | 2 | |
|
||||
| Maximum G-Force | | 2 | |
|
||||
| Minimum Z axis G-Force | | 2 | |
|
||||
| Maximum Z axis G-Force | | 2 | |
|
||||
| Blackbox file number | Blackbox recording | 2 | |
|
||||
| Disarm method | | 1 & 2 | |
|
||||
| Settings save status | | 1 & 2 | Shows a message if the settings are being saved or have been saved on disarm. |
|
||||
|
||||
## Configuration
|
||||
There are a couple of settings that allow you to adjust parts of the post flights statistics.
|
||||
|
||||
- `osd_stats_page_auto_swap_time` allows you to specify how long each stats page is displayed [seconds]. Reverts to manual control when Roll stick used to change pages. Disabled when set to 0.
|
||||
- `osd_stats_energy_unit` allows you to choose the unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour). Default is MAH.
|
||||
- `osd_stats_show_metric_efficiency` if you use non-metric units on your OSD. Enabling this option will also show the efficiency in metric.
|
||||
|
|
|
@ -1,10 +1,10 @@
|
|||
# INAV Programming Framework
|
||||
|
||||
INAV Programming Framework (IPF) is a mechanism that allows you to to create
|
||||
INAV Programming Framework (IPF) is a mechanism that allows you to to create
|
||||
custom functionality in INAV. You can choose for certain actions to be done,
|
||||
based on custom conditions you select.
|
||||
|
||||
Logic conditions can be based on things such as RC channel values, switches, altitude,
|
||||
Logic conditions can be based on things such as RC channel values, switches, altitude,
|
||||
distance, timers, etc. The conditions you create can also make use of other conditions
|
||||
you've entered previously.
|
||||
The results can be used in:
|
||||
|
@ -24,6 +24,8 @@ INAV Programming Framework consists of:
|
|||
IPF can be edited using INAV Configurator user interface, or via CLI. To use COnfigurator, click the tab labeled
|
||||
"Programming". The various options shown in Configurator are described below.
|
||||
|
||||
**Note:** IPF uses integer math. If your programming line returns a decimal, it will be truncated to an integer. So if your math is `1` / `3` = , IPF will truncate the decimal and return `0`.
|
||||
|
||||
## Logic Conditions
|
||||
|
||||
### CLI
|
||||
|
@ -44,119 +46,123 @@ IPF can be edited using INAV Configurator user interface, or via CLI. To use COn
|
|||
|
||||
| Operation ID | Name | Notes |
|
||||
|---------------|-------------------------------|-------|
|
||||
| 0 | TRUE | Always evaluates as true |
|
||||
| 1 | EQUAL | Evaluates `false` if `false` or `0` |
|
||||
| 2 | GREATER_THAN | `true` if `Operand A` is a higher value than `Operand B` |
|
||||
| 3 | LOWER_THAN | `true` if `Operand A` is a lower value than `Operand B` |
|
||||
| 4 | LOW | `true` if `<1333` |
|
||||
| 5 | MID | `true` if `>=1333 and <=1666` |
|
||||
| 6 | HIGH | `true` if `>1666` |
|
||||
| 0 | True | Always evaluates as true |
|
||||
| 1 | Equal (A=B) | Evaluates `false` if `false` or `0` |
|
||||
| 2 | Greater Than (A>B) | `true` if `Operand A` is a higher value than `Operand B` |
|
||||
| 3 | Lower Than (A<B) | `true` if `Operand A` is a lower value than `Operand B` |
|
||||
| 4 | Low | `true` if `<1333` |
|
||||
| 5 | Mid | `true` if `>=1333 and <=1666` |
|
||||
| 6 | High | `true` if `>1666` |
|
||||
| 7 | AND | `true` if `Operand A` and `Operand B` are the same value or both `true` |
|
||||
| 8 | OR | `true` if `Operand A` and/or `OperandB` is `true` |
|
||||
| 9 | XOR | `true` if `Operand A` or `Operand B` is `true`, but not both |
|
||||
| 10 | NAND | `false` if `Operand A` and `Operand B` are both `true`|
|
||||
| 11 | NOR | `true` if `Operand A` and `Operand B` are both `false` |
|
||||
| 12 | NOT | The boolean opposite to `Operand A` |
|
||||
| 13 | Sticky | `Operand A` is the activation operator, `Operand B` is the deactivation operator. After the activation is `true`, the operator will return `true` until Operand B is evaluated as `true`|
|
||||
| 14 | Basic: Add | Add `Operand A` to `Operand B` and returns the result |
|
||||
| 15 | Basic: Subtract | Substract `Operand B` from `Operand A` and returns the result |
|
||||
| 16 | Basic: Multiply | Multiply `Operand A` by `Operand B` and returns the result |
|
||||
| 17 | Basic: Divide | Divide `Operand A` by `Operand B` and returns the result |
|
||||
| 18 | Set GVAR | Store value from `Operand B` into the Global Variable addressed by
|
||||
`Operand A`. Bear in mind, that operand `Global Variable` means: Value stored in Global Variable of an index! To store in GVAR 1 use `Value 1` not `Global Variable 1` |
|
||||
| 19 | Increase GVAR | Increase the GVAR indexed by `Operand A` (use `Value 1` for Global Variable 1) with value from `Operand B` |
|
||||
| 20 | Decrease GVAR | Decrease the GVAR indexed by `Operand A` (use `Value 1` for Global Variable 1) with value from `Operand B` |
|
||||
| 12 | NOT | The boolean opposite to `Operand A` |
|
||||
| 13 | Sticky | `Operand A` is the activation operator, `Operand B` is the deactivation operator. After the activation is `true`, the operator will return `true` until Operand B is evaluated as `true`|
|
||||
| 14 | Basic: Add | Add `Operand A` to `Operand B` and returns the result |
|
||||
| 15 | Basic: Subtract | Substract `Operand B` from `Operand A` and returns the result |
|
||||
| 16 | Basic: Multiply | Multiply `Operand A` by `Operand B` and returns the result |
|
||||
| 17 | Basic: Divide | Divide `Operand A` by `Operand B` and returns the result. NOTE: If `Operand B` = `0`, the `Divide` operation will simply return `Operand A`|
|
||||
| 18 | Set GVAR | Store value from `Operand B` into the Global Variable addressed by `Operand A`. Bear in mind, that operand `Global Variable` means: Value stored in Global Variable of an index! To store in GVAR 1 use `Value 1` not `Global Variable 1` |
|
||||
| 19 | Increase GVAR | Increase the GVAR indexed by `Operand A` (use `Value 1` for Global Variable 1) with value from `Operand B` |
|
||||
| 20 | Decrease GVAR | Decrease the GVAR indexed by `Operand A` (use `Value 1` for Global Variable 1) with value from `Operand B` |
|
||||
| 21 | Set IO Port | Set I2C IO Expander pin `Operand A` to value of `Operand B`. `Operand A` accepts values `0-7` and `Operand B` accepts `0` and `1` |
|
||||
| 22 | OVERRIDE_ARMING_SAFETY | Allows the craft to arm on any angle even without GPS fix. WARNING: This bypasses all safety checks, even that the throttle is low, so use with caution. If you only want to check for certain conditions, such as arm without GPS fix. You will need to add logic conditions to check the throttle is low. |
|
||||
| 23 | OVERRIDE_THROTTLE_SCALE | Override throttle scale to the value defined by operand. Operand type `0` and value `50` means throttle will be scaled by 50%. |
|
||||
| 24 | SWAP_ROLL_YAW | basically, when activated, yaw stick will control roll and roll stick will control yaw. Required for tail-sitters VTOL during vertical-horizonral transition when body frame changes |
|
||||
| 25 | SET_VTX_POWER_LEVEL | Sets VTX power level. Accepted values are `0-3` for SmartAudio and `0-4` for Tramp protocol |
|
||||
| 26 | INVERT_ROLL | Inverts ROLL axis input for PID/PIFF controller |
|
||||
| 27 | INVERT_PITCH | Inverts PITCH axis input for PID/PIFF controller |
|
||||
| 28 | INVERT_YAW | Inverts YAW axis input for PID/PIFF controller |
|
||||
| 29 | OVERRIDE_THROTTLE | Override throttle value that is fed to the motors by mixer. Operand is scaled in us. `1000` means throttle cut, `1500` means half throttle |
|
||||
| 30 | SET_VTX_BAND | Sets VTX band. Accepted values are `1-5` |
|
||||
| 31 | SET_VTX_CHANNEL | Sets VTX channel. Accepted values are `1-8` |
|
||||
| 32 | SET_OSD_LAYOUT | Sets OSD layout. Accepted values are `0-3` |
|
||||
| 33 | Trigonometry: Sine | Computes SIN of `Operand A` value in degrees. Output is multiplied by `Operand B` value. If `Operand B` is `0`, result is multiplied by `500` |
|
||||
| 34 | Trigonometry: Cosine | Computes COS of `Operand A` value in degrees. Output is multiplied by `Operand B` value. If `Operand B` is `0`, result is multiplied by `500` |
|
||||
| 35 | Trigonometry: Tangent | Computes TAN of `Operand A` value in degrees. Output is multiplied by `Operand B` value. If `Operand B` is `0`, result is multiplied by `500` |
|
||||
| 36 | MAP_INPUT | Scales `Operand A` from [`0` : `Operand B`] to [`0` : `1000`]. Note: input will be constrained and then scaled |
|
||||
| 37 | MAP_OUTPUT | Scales `Operand A` from [`0` : `1000`] to [`0` : `Operand B`]. Note: input will be constrained and then scaled |
|
||||
| 38 | RC_CHANNEL_OVERRIDE | Overrides channel set by `Operand A` to value of `Operand B`. Note operand A should normally be set as a "Value", NOT as "Get RC Channel"|
|
||||
| 39 | SET_HEADING_TARGET | Sets heading-hold target to `Operand A`, in degrees. Value wraps-around. |
|
||||
| 40 | Modulo | Modulo. Divide `Operand A` by `Operand B` and returns the remainder |
|
||||
| 41 | LOITER_RADIUS_OVERRIDE | Sets the loiter radius to `Operand A` [`0` : `100000`] in cm. If the value is lower than the loiter radius set in the **Advanced Tuning**, that will be used. |
|
||||
| 42 | SET_PROFILE | Sets the active config profile (PIDFF/Rates/Filters/etc) to `Operand A`. `Operand A` must be a valid profile number, currently from 1 to 3. If not, the profile will not change |
|
||||
| 43 | Use Lowest Value | Finds the lowest value of `Operand A` and `Operand B` |
|
||||
| 44 | Use Highest Value | Finds the highest value of `Operand A` and `Operand B` |
|
||||
| 45 | FLIGHT_AXIS_ANGLE_OVERRIDE | Sets the target attitude angle for axis. In other words, when active, it enforces Angle mode (Heading Hold for Yaw) on this axis (Angle mode does not have to be active). `Operand A` defines the axis: `0` - Roll, `1` - Pitch, `2` - Yaw. `Operand B` defines the angle in degrees |
|
||||
| 46 | FLIGHT_AXIS_RATE_OVERRIDE | Sets the target rate (rotation speed) for axis. `Operand A` defines the axis: `0` - Roll, `1` - Pitch, `2` - Yaw. `Operand B` defines the rate in degrees per second |
|
||||
| 47 | EDGE | Momentarily true when triggered by `Operand A`. `Operand A` is the activation operator [`boolean`], `Operand B` _(Optional)_ is the time for the edge to stay active [ms]. After activation, operator will return `true` until the time in Operand B is reached. If a pure momentary edge is wanted. Just leave `Operand B` as the default `Value: 0` setting. |
|
||||
| 48 | DELAY | Delays activation after being triggered. This will return `true` when `Operand A` _is_ true, and the delay time in `Operand B` [ms] has been exceeded. |
|
||||
| 49 | TIMER | A simple on - off timer. `true` for the duration of `Operand A` [ms]. Then `false` for the duration of `Operand B` [ms]. |
|
||||
| 50 | DELTA | This returns `true` when the value of `Operand A` has changed by the value of `Operand B` or greater within 100ms. |
|
||||
| 51 | APPROX_EQUAL | `true` if `Operand B` is within 1% of `Operand A`. |
|
||||
| 52 | LED_PIN_PWM | Value `Operand A` from [`0` : `100`] starts PWM generation on LED Pin. See [LED pin PWM](LED%20pin%20PWM.md). Any other value stops PWM generation (stop to allow ws2812 LEDs updates in shared modes)|
|
||||
| 22 | Override Arming Safety | Allows the craft to arm on any angle even without GPS fix. WARNING: This bypasses all safety checks, even that the throttle is low, so use with caution. If you only want to check for certain conditions, such as arm without GPS fix. You will need to add logic conditions to check the throttle is low. |
|
||||
| 23 | Override Throttle Scale | Override throttle scale to the value defined by operand. Operand type `0` and value `50` means throttle will be scaled by 50%. |
|
||||
| 24 | Swap Roll & Yaw | basically, when activated, yaw stick will control roll and roll stick will control yaw. Required for tail-sitters VTOL during vertical-horizonral transition when body frame changes |
|
||||
| 25 | Set VTx Power Level | Sets VTX power level. Accepted values are `0-3` for SmartAudio and `0-4` for Tramp protocol |
|
||||
| 26 | Invert Roll | Inverts ROLL axis input for PID/PIFF controller |
|
||||
| 27 | Invert Pitch | Inverts PITCH axis input for PID/PIFF controller |
|
||||
| 28 | Invert Yaw | Inverts YAW axis input for PID/PIFF controller |
|
||||
| 29 | Override Throttlw | Override throttle value that is fed to the motors by mixer. Operand is scaled in us. `1000` means throttle cut, `1500` means half throttle |
|
||||
| 30 | Set VTx Band | Sets VTX band. Accepted values are `1-5` |
|
||||
| 31 | Set VTx Channel | Sets VTX channel. Accepted values are `1-8` |
|
||||
| 32 | Set OSD Layout | Sets OSD layout. Accepted values are `0-3` |
|
||||
| 33 | Trigonometry: Sine | Computes SIN of `Operand A` value in degrees. Output is multiplied by `Operand B` value. If `Operand B` is `0`, result is multiplied by `500` |
|
||||
| 34 | Trigonometry: Cosine | Computes COS of `Operand A` value in degrees. Output is multiplied by `Operand B` value. If `Operand B` is `0`, result is multiplied by `500` |
|
||||
| 35 | Trigonometry: Tangent | Computes TAN of `Operand A` value in degrees. Output is multiplied by `Operand B` value. If `Operand B` is `0`, result is multiplied by `500` |
|
||||
| 36 | Map Input | Scales `Operand A` from [`0` : `Operand B`] to [`0` : `1000`]. Note: input will be constrained and then scaled |
|
||||
| 37 | Map Output | Scales `Operand A` from [`0` : `1000`] to [`0` : `Operand B`]. Note: input will be constrained and then scaled |
|
||||
| 38 | Override RC Channel | Overrides channel set by `Operand A` to value of `Operand B`. Note operand A should normally be set as a "Value", NOT as "Get RC Channel"|
|
||||
| 39 | Set Heading Target | Sets heading-hold target to `Operand A`, in centidegrees. Value wraps-around. |
|
||||
| 40 | Modulo | Modulo. Divide `Operand A` by `Operand B` and returns the remainder |
|
||||
| 41 | Override Loiter Radius | Sets the loiter radius to `Operand A` [`0` : `100000`] in cm. Must be larger than the loiter radius set in the **Advanced Tuning**. |
|
||||
| 42 | Set Control Profile | Sets the active config profile (PIDFF/Rates/Filters/etc) to `Operand A`. `Operand A` must be a valid profile number, currently from 1 to 3. If not, the profile will not change |
|
||||
| 43 | Use Lowest Value | Finds the lowest value of `Operand A` and `Operand B` |
|
||||
| 44 | Use Highest Value | Finds the highest value of `Operand A` and `Operand B` |
|
||||
| 45 | Flight Axis Angle Override | Sets the target attitude angle for axis. In other words, when active, it enforces Angle mode (Heading Hold for Yaw) on this axis (Angle mode does not have to be active). `Operand A` defines the axis: `0` - Roll, `1` - Pitch, `2` - Yaw. `Operand B` defines the angle in degrees |
|
||||
| 46 | Flight Axis Rate Override | Sets the target rate (rotation speed) for axis. `Operand A` defines the axis: `0` - Roll, `1` - Pitch, `2` - Yaw. `Operand B` defines the rate in degrees per second |
|
||||
| 47 | Edge | Momentarily true when triggered by `Operand A`. `Operand A` is the activation operator [`boolean`], `Operand B` _(Optional)_ is the time for the edge to stay active [ms]. After activation, operator will return `true` until the time in Operand B is reached. If a pure momentary edge is wanted. Just leave `Operand B` as the default `Value: 0` setting. |
|
||||
| 48 | Delay | Delays activation after being triggered. This will return `true` when `Operand A` _is_ true, and the delay time in `Operand B` [ms] has been exceeded. |
|
||||
| 49 | Timer | A simple on - off timer. `true` for the duration of `Operand A` [ms]. Then `false` for the duration of `Operand B` [ms]. |
|
||||
| 50 | Delta (|A| >= B) | This returns `true` when the value of `Operand A` has changed by the value of `Operand B` or greater within 100ms. |
|
||||
| 51 | Approx Equals (A ~ B) | `true` if `Operand B` is within 1% of `Operand A`. |
|
||||
| 52 | LED Pin PWM | Value `Operand A` from [`0` : `100`] starts PWM generation on LED Pin. See [LED pin PWM](LED%20pin%20PWM.md). Any other value stops PWM generation (stop to allow ws2812 LEDs updates in shared modes). |
|
||||
| 53 | Disable GPS Sensor Fix | Disables the GNSS sensor fix. For testing GNSS failure. |
|
||||
| 54 | Mag calibration | Trigger a magnetometer calibration. |
|
||||
|
||||
### Operands
|
||||
|
||||
| Operand Type | Name | Notes |
|
||||
|---------------|-----------------------|-------|
|
||||
| 0 | VALUE | Value derived from `value` field |
|
||||
| 1 | GET_RC_CHANNEL | `value` points to RC channel number, indexed from 1 |
|
||||
| 2 | FLIGHT | `value` points to flight parameter table |
|
||||
| 3 | FLIGHT_MODE | `value` points to flight modes table |
|
||||
| 4 | LC | `value` points to other logic condition ID |
|
||||
| 5 | GVAR | Value stored in Global Variable indexed by `value`. `GVAR 1` means: value in GVAR 1 |
|
||||
| 5 | PID | Output of a Programming PID indexed by `value`. `PID 1` means: value in PID 1 |
|
||||
| 0 | Value | Value derived from `value` field |
|
||||
| 1 | Get RC Channel | `value` points to RC channel number, indexed from 1 |
|
||||
| 2 | Flight | `value` points to **Flight** Parameters table |
|
||||
| 3 | Flight Mode | `value` points to **Flight_Mode** table |
|
||||
| 4 | Logic Condition | `value` points to other logic condition ID |
|
||||
| 5 | Get Global Variable | Value stored in Global Variable indexed by `value`. `GVAR 1` means: value in GVAR 1 |
|
||||
| 5 | Programming PID | Output of a Programming PID indexed by `value`. `PID 1` means: value in PID 1 |
|
||||
| 6 | Waypoints | `value` points to the **Waypoint** parameter table |
|
||||
|
||||
#### FLIGHT
|
||||
#### Flight Parameters
|
||||
|
||||
| Operand Value | Name | Notes |
|
||||
|---------------|-------------------------------|-------|
|
||||
| 0 | ARM_TIMER | in `seconds` |
|
||||
| 1 | HOME_DISTANCE | in `meters` |
|
||||
| 2 | TRIP_DISTANCE | in `meters` |
|
||||
| 3 | RSSI | |
|
||||
| 4 | VBAT | in `Volts * 100`, eg. `12.1V` is `1210` |
|
||||
| 5 | CELL_VOLTAGE | in `Volts * 100`, eg. `12.1V` is `1210` |
|
||||
| 6 | CURRENT | in `Amps * 100`, eg. `9A` is `900` |
|
||||
| 7 | MAH_DRAWN | in `mAh` |
|
||||
| 8 | GPS_SATS | |
|
||||
| 9 | GROUD_SPEED | in `cm/s` |
|
||||
| 10 | 3D_SPEED | in `cm/s` |
|
||||
| 11 | AIR_SPEED | in `cm/s` |
|
||||
| 12 | ALTITUDE | in `cm` |
|
||||
| 13 | VERTICAL_SPEED | in `cm/s` |
|
||||
| 14 | TROTTLE_POS | in `%` |
|
||||
| 15 | ATTITUDE_ROLL | in `degrees` |
|
||||
| 16 | ATTITUDE_PITCH | in `degrees` |
|
||||
| 17 | IS_ARMED | boolean `0`/`1` |
|
||||
| 18 | IS_AUTOLAUNCH | boolean `0`/`1` |
|
||||
| 19 | IS_ALTITUDE_CONTROL | boolean `0`/`1` |
|
||||
| 20 | IS_POSITION_CONTROL | boolean `0`/`1` |
|
||||
| 21 | IS_EMERGENCY_LANDING | boolean `0`/`1` |
|
||||
| 22 | IS_RTH | boolean `0`/`1` |
|
||||
| 23 | IS_LANDING | boolean `0`/`1` |
|
||||
| 24 | IS_FAILSAFE | boolean `0`/`1` |
|
||||
| 25 | STABILIZED_ROLL | Roll PID controller output `[-500:500]` |
|
||||
| 26 | STABILIZED_PITCH | Pitch PID controller output `[-500:500]` |
|
||||
| 27 | STABILIZED_YAW | Yaw PID controller output `[-500:500]` |
|
||||
| 28 | 3D HOME_DISTANCE | in `meters`, calculated from HOME_DISTANCE and ALTITUDE using Pythagorean theorem |
|
||||
| 29 | CROSSFIRE LQ | Crossfire Link quality as returned by the CRSF protocol |
|
||||
| 30 | CROSSFIRE SNR | Crossfire SNR as returned by the CRSF protocol |
|
||||
| 31 | GPS_VALID | boolean `0`/`1`. True when the GPS has a valid 3D Fix |
|
||||
| 32 | LOITER_RADIUS | The current loiter radius in cm. |
|
||||
| 33 | ACTIVE_PROFILE | integer for the active config profile `[1..MAX_PROFILE_COUNT]` |
|
||||
| 34 | BATT_CELLS | Number of battery cells detected |
|
||||
| 35 | AGL_STATUS | boolean `1` when AGL can be trusted, `0` when AGL estimate can not be trusted |
|
||||
| 36 | AGL | integer Above The Groud Altitude in `cm` |
|
||||
| 37 | RANGEFINDER_RAW | integer raw distance provided by the rangefinder in `cm` |
|
||||
| 38 | ACTIVE_MIXER_PROFILE | Which mixers are currently active (for vtol etc) |
|
||||
| 39 | MIXER_TRANSITION_ACTIVE | Currently switching between mixers (quad to plane etc) |
|
||||
| 40 | ATTITUDE_YAW | current heading (yaw) in `degrees` |
|
||||
| 41 | FW Land Sate | integer `1` - `5`, indicates the status of the FW landing, 0 Idle, 1 Downwind, 2 Base Leg, 3 Final Approach, 4 Glide, 5 Flare |
|
||||
| Operand Value | Name | Notes |
|
||||
|---------------|---------------------------------------|-------|
|
||||
| 0 | ARM Timer [s] | Time since armed in `seconds` |
|
||||
| 1 | Home Distance [m] | distance from home in `meters` |
|
||||
| 2 | Trip distance [m] | Trip distance in `meters` |
|
||||
| 3 | RSSI | |
|
||||
| 4 | Vbat [centi-Volt] [1V = 100] | VBAT Voltage in `Volts * 100`, eg. `12.1V` is `1210` |
|
||||
| 5 | Cell voltage [centi-Volt] [1V = 100] | Average cell voltage in `Volts * 100`, eg. `12.1V` is `1210` |
|
||||
| 6 | Current [centi-Amp] [1A = 100] | Current in `Amps * 100`, eg. `9A` is `900` |
|
||||
| 7 | Current drawn [mAh] | Total used current in `mAh` |
|
||||
| 8 | GPS Sats | |
|
||||
| 9 | Ground speed [cm/s] | Ground speed in `cm/s` |
|
||||
| 10 | 3D speed [cm/s] | 3D speed in `cm/s` |
|
||||
| 11 | Air speed [cm/s] | Air speed in `cm/s` |
|
||||
| 12 | Altitude [cm] | Altitude in `cm` |
|
||||
| 13 | Vertical speed [cm/s] | Vertical speed in `cm/s` |
|
||||
| 14 | Throttle position [%] | Throttle position in `%` |
|
||||
| 15 | Roll [deg] | Roll attitude in `degrees` |
|
||||
| 16 | Pitch [deg] | Pitch attitude in `degrees` |
|
||||
| 17 | Is Armed | Is the system armed? boolean `0`/`1` |
|
||||
| 18 | Is Autolaunch | Is auto launch active? boolean `0`/`1` |
|
||||
| 19 | Is Controlling Altitude | Is altitude being controlled? boolean `0`/`1` |
|
||||
| 20 | Is Controlling Position | Is the position being controlled? boolean `0`/`1` |
|
||||
| 21 | Is Emergency Landing | Is the aircraft emergency landing? boolean `0`/`1` |
|
||||
| 22 | Is RTH | Is RTH active? boolean `0`/`1` |
|
||||
| 23 | Is Landing | Is the aircaft automatically landing? boolean `0`/`1` |
|
||||
| 24 | Is Failsafe | Is the flight controller in a failsafe? boolean `0`/`1` |
|
||||
| 25 | Stabilized Roll | Roll PID controller output `[-500:500]` |
|
||||
| 26 | Stabilized Pitch | Pitch PID controller output `[-500:500]` |
|
||||
| 27 | Stabilized Yaw | Yaw PID controller output `[-500:500]` |
|
||||
| 28 | 3D home distance [m] | 3D distance to home in `meters`. Calculated from Home distance and Altitude using Pythagorean theorem |
|
||||
| 29 | CRSF LQ | Link quality as returned by the CRSF protocol |
|
||||
| 30 | CRSF SNR | SNR as returned by the CRSF protocol |
|
||||
| 31 | GPS Valid Fix | Boolean `0`/`1`. True when the GPS has a valid 3D Fix |
|
||||
| 32 | Loiter Radius [cm] | The current loiter radius in cm. |
|
||||
| 33 | Active Control Profile | Integer for the active config profile `[1..MAX_PROFILE_COUNT]` |
|
||||
| 34 | Battery cells | Number of battery cells detected |
|
||||
| 35 | AGL status [0/1] | Boolean `1` when AGL can be trusted, `0` when AGL estimate can not be trusted |
|
||||
| 36 | AGL [cm] | Integer altitude above The Groud Altitude in `cm` |
|
||||
| 37 | Rangefinder [cm] | Integer raw distance provided by the rangefinder in `cm` |
|
||||
| 38 | Active Mixer Profile | Which mixer is currently active (for vtol etc) |
|
||||
| 39 | Mixer Transition Active | Boolean `0`/`1`. Are we currently switching between mixers (quad to plane etc) |
|
||||
| 40 | Yaw [deg] | Current heading (yaw) in `degrees` |
|
||||
| 41 | FW Land Sate | Integer `1` - `5`, indicates the status of the FW landing, 0 Idle, 1 Downwind, 2 Base Leg, 3 Final Approach, 4 Glide, 5 Flare |
|
||||
| 42 | Current battery profile | The active battery profile. Integer `[1..MAX_PROFILE_COUNT]` |
|
||||
| 43 | Flown Loiter Radius [m] | The actual loiter radius flown by a fixed wing during hold modes, in `meters` |
|
||||
|
||||
#### FLIGHT_MODE
|
||||
|
||||
|
@ -164,22 +170,22 @@ The flight mode operands return `true` when the mode is active. These are modes
|
|||
|
||||
| Operand Value | Name | Notes |
|
||||
|---------------|-------------------|-------|
|
||||
| 0 | FAILSAFE | `true` when a **Failsafe** state has been triggered. |
|
||||
| 1 | MANUAL | `true` when you are in the **Manual** flight mode. |
|
||||
| 0 | Failsafe | `true` when a **Failsafe** state has been triggered. |
|
||||
| 1 | Manual | `true` when you are in the **Manual** flight mode. |
|
||||
| 2 | RTH | `true` when you are in the **Return to Home** flight mode. |
|
||||
| 3 | POSHOLD | `true` when you are in the **Position Hold** or **Loiter** flight modes. |
|
||||
| 4 | CRUISE | `true` when you are in the **Cruise** flight mode. |
|
||||
| 5 | ALTHOLD | `true` when you the **Altitude Hold** flight mode modifier is active. |
|
||||
| 6 | ANGLE | `true` when you are in the **Angle** flight mode. |
|
||||
| 7 | HORIZON | `true` when you are in the **Horizon** flight mode. |
|
||||
| 8 | AIR | `true` when you the **Airmode** flight mode modifier is active. |
|
||||
| 9 | USER1 | `true` when the **USER 1** mode is active. |
|
||||
| 10 | USER2 | `true` when the **USER 2** mode is active. |
|
||||
| 11 | COURSE_HOLD | `true` when you are in the **Course Hold** flight mode. |
|
||||
| 12 | USER3 | `true` when the **USER 3** mode is active. |
|
||||
| 13 | USER4 | `true` when the **USER 4** mode is active. |
|
||||
| 14 | ACRO | `true` when you are in the **Acro** flight mode. |
|
||||
| 15 | WAYPOINT_MISSION | `true` when you are in the **WP Mission** flight mode. |
|
||||
| 3 | Position Hold | `true` when you are in the **Position Hold** or **Loiter** flight modes. |
|
||||
| 4 | Cruise | `true` when you are in the **Cruise** flight mode. |
|
||||
| 5 | Altitude Hold | `true` when you the **Altitude Hold** flight mode modifier is active. |
|
||||
| 6 | Angle | `true` when you are in the **Angle** flight mode. |
|
||||
| 7 | Horizon | `true` when you are in the **Horizon** flight mode. |
|
||||
| 8 | Air | `true` when you the **Airmode** flight mode modifier is active. |
|
||||
| 9 | USER 1 | `true` when the **USER 1** mode is active. |
|
||||
| 10 | USER 2 | `true` when the **USER 2** mode is active. |
|
||||
| 11 | Course Hold | `true` when you are in the **Course Hold** flight mode. |
|
||||
| 12 | USER 3 | `true` when the **USER 3** mode is active. |
|
||||
| 13 | USER 4 | `true` when the **USER 4** mode is active. |
|
||||
| 14 | Acro | `true` when you are in the **Acro** flight mode. |
|
||||
| 15 | Waypoint Mission | `true` when you are in the **WP Mission** flight mode. |
|
||||
|
||||
#### WAYPOINTS
|
||||
|
||||
|
@ -212,7 +218,7 @@ The flight mode operands return `true` when the mode is active. These are modes
|
|||
| JUMP | 6 |
|
||||
| SET_HEAD | 7 |
|
||||
| LAND | 8 |
|
||||
|
||||
|
||||
### Flags
|
||||
|
||||
All flags are reseted on ARM and DISARM event.
|
||||
|
@ -228,8 +234,15 @@ All flags are reseted on ARM and DISARM event.
|
|||
|
||||
`gvar <index> <default value> <min> <max>`
|
||||
|
||||
**Note:** Global Variables (GVARs) are limited to integers between negative `-32768` and positive `32767`.
|
||||
|
||||
## Programming PID
|
||||
|
||||
IPF makes a set of general user PIDFF controllers avaliable for use in your program. These PIDFF controllers are not tied to any roll/pitch/yaw profiles or other controls.
|
||||
The output of these controllers can be used in an IPF program by using the `Programming PID` operand.
|
||||
The `<setpoint value>` of the controller is the target value for the controller to hit. The `<measurement value>` is the measurement of the current value. For instance, `<setpoint value>` could be the speed you want to go, and `<measurement value>` is the current speed.
|
||||
P, I, D, and FF values will need to be manually adjusted to determine the appropriate value for the program and controller.
|
||||
|
||||
`pid <index> <enabled> <setpoint type> <setpoint value> <measurement type> <measurement value> <P gain> <I gain> <D gain> <FF gain>`
|
||||
|
||||
* `<index>` - ID of PID Controller, starting from `0`
|
||||
|
@ -329,11 +342,9 @@ Steps:
|
|||
|
||||
## Common issues / questions about IPF
|
||||
|
||||
One common mistake involves setting RC channel values. To override (set) the
|
||||
One common mistake involves setting RC channel values. To override (set) the
|
||||
value of a specific RC channel, choose "Override RC value", then for operand A
|
||||
choose *value* and enter the channel number. Choosing "get RC value" is a common mistake,
|
||||
which does something other than what you probably want.
|
||||
|
||||

|
||||
|
||||
|
||||
|
|
|
@ -20,6 +20,23 @@ Following rangefinders are supported:
|
|||
* UIB - experimental
|
||||
* MSP - experimental
|
||||
* TOF10120 - small & lightweight laser range sensor, usable up to 200cm
|
||||
* TERARANGER EVO - 30cm to 600cm, depends on version https://www.terabee.com/sensors-modules/lidar-tof-range-finders/#individual-distance-measurement-sensors
|
||||
* NRA15/NRA24 - experimental, UART version
|
||||
|
||||
#### NRA15/NRA24
|
||||
NRA15/NRA24 from nanoradar use US-D1_V0 or NRA protocol, it depends which firmware you use. Radar can be set by firmware
|
||||
to two different resolutions. See table below.
|
||||
|
||||
| Radar | Protocol | Resolution | Name in configurator |
|
||||
|-------|----------|-----------------|----------------------|
|
||||
| NRA15 | US-D1_V0 | 0-30m (+-4cm) | USD1_V0 |
|
||||
| NRA15 | NRA | 0-30m (+-4cm) | NRA |
|
||||
| NRA15 | NRA | 0-100m (+-10cm) | NRA |
|
||||
| NRA24 | US-D1_V0 | 0-50m (+-4cm) | USD1_V0 |
|
||||
| NRA24 | US-D1_V0 | 0-200m (+-10cm) | USD1_V0 |
|
||||
| NRA24 | NRA | 0-50m (+-4cm) | NRA |
|
||||
| NRA24 | NRA | 0-200m (+-10cm) | NRA |
|
||||
|
||||
|
||||
## Connections
|
||||
|
||||
|
|
|
@ -205,7 +205,7 @@ Note:
|
|||
|
||||
## SIM (SITL) Joystick
|
||||
|
||||
Enables the use of a joystick in the INAV SITL with a flight simulator. See the [SITL documentation](SITL/SITL).
|
||||
Enables the use of a joystick in the INAV SITL with a flight simulator. See the [SITL documentation](SITL/SITL.md).
|
||||
|
||||
## Configuration
|
||||
|
||||
|
|
25
docs/SBUS2_Telemetry.md
Normal file
25
docs/SBUS2_Telemetry.md
Normal file
|
@ -0,0 +1,25 @@
|
|||
# Futaba SBUS2 Telemetry
|
||||
|
||||
Basic experimental support for SBUS2 telemetry has been added to INAV 8.0.0. Currently it is limited to F7 and H7 mcus only. The main reason it is limited to those MCUs is due to the requirement for an inverted UART signal and the SBUS pads in F405 usually are not bi-directional.
|
||||
|
||||
The basic sensors have been tested with a Futaba T16IZ running software version 6.0E.
|
||||
|
||||
An alternative to using INAV's SBUS2 support is to use SBS-01ML MAVlink Telemetry Drone Sensor instead. (not tested and not supported with older futaba radios, including my 16IZ).
|
||||
|
||||
# Wiring
|
||||
The SBUS2 signal should be connected to the TX PIN, not the RX PIN, like on a traditional SBUS setup.
|
||||
|
||||
# Sensor mapping
|
||||
|
||||
The following fixed sensor mapping is used:
|
||||
|
||||
| Slot | Sensort Type | Info |
|
||||
| --- | --- | --- |
|
||||
| 1 | Voltage | Pack voltage and cell voltage |
|
||||
| 3 | Current | Capacity = used mAh |
|
||||
| 6 | rpm sensor | motor rpm. Need to set geat ratio to 1.0 |
|
||||
| 7 | Temperature | ESC Temperature |
|
||||
| 8 | GPS | |
|
||||
| 16 | Temperature | IMU Temperature |
|
||||
| 17 | Temperature | Baro Temperature |
|
||||
| 18-25 | Temperature | Temperature sensor 0-7 |
|
|
@ -16,6 +16,10 @@ Currently supported are
|
|||
|
||||
INAV SITL communicates for sensor data and control directly with the corresponding simulator, see the documentation of the individual simulators and the Configurator or the command line options.
|
||||
|
||||
AS SITL is still an inav software, but running on PC, it is possible to use HITL interface for communication.
|
||||
|
||||
INAV-X-Plane-HITL plugin https://github.com/RomanLut/INAV-X-Plane-HITL can be used with SITL.
|
||||
|
||||
## Sensors
|
||||
The following sensors are emulated:
|
||||
- IMU (Gyro, Accelerometer)
|
||||
|
@ -30,13 +34,18 @@ The following sensors are emulated:
|
|||
|
||||
Select "FAKE" as type for all mentioned, so that they receive the data from the simulator.
|
||||
|
||||
## Serial ports+
|
||||
UARTs are replaced by TCP starting with port 5760 ascending. UART 1 port 5760, UART2 5761, ...
|
||||
By default, UART1 and UART2 are available as MSP connections. Other UARTs will have TCP listeners if they have an INAV function assigned.
|
||||
To connect the Configurator to SITL: Select TCP and connect to ```localhost:5760``` (or ```127.0.0.1:5760``` if your OS doesn't understand `localhost`) (if SITL is running on the same machine).
|
||||
## Serial ports
|
||||
UARTs are replaced by TCP starting with port 5760 ascending. UART1 is mapped to port 5760, UART2 to 5761, etc.
|
||||
|
||||
By default, UART1 and UART2 are configured for MSP connections. Other UARTs will have TCP listeners if they have an INAV function assigned.
|
||||
|
||||
To connect the Configurator to SITL, select "SITL".
|
||||
|
||||
Alternativelly, select "TCP" and connect to ```localhost:5760``` (or ```127.0.0.1:5760``` if your OS doesn't understand `localhost`) (if SITL is running on the same machine).
|
||||
|
||||
IPv4 and IPv6 are supported, either raw addresses or host-name lookup.
|
||||
|
||||
The assignment and status of user UART/TCP connections is displayed on the console.
|
||||
The assignment and status of used UART/TCP connections is displayed on the console.
|
||||
|
||||
```
|
||||
INAV 6.1.0 SITL
|
||||
|
@ -51,39 +60,73 @@ INAV 6.1.0 SITL
|
|||
All other interfaces (I2C, SPI, etc.) are not emulated.
|
||||
|
||||
## Remote control
|
||||
MSP_RX (TCP/IP) or joystick (via simulator) or serial receiver via USB/Serial interface are supported.
|
||||
Multiple methods for connecting RC Controllers are available:
|
||||
- MSP_RX (TCP/IP)
|
||||
- joystick (via simulator)
|
||||
- serial receiver via USB to serial converter
|
||||
- any receiver with proxy flight controller
|
||||
|
||||
|
||||
### MSP_RX
|
||||
|
||||
MSP_RX is the default, 18 channels are supported over TCP/IP serial emulation.
|
||||
MSP_RX is the default, 18 channels are supported over TCP/IP connection.
|
||||
|
||||
### Joystick interface
|
||||
Only 8 channels are supported.
|
||||
Select "SIM (SITL)" as the receiver and set up a joystick in the simulator, details of which can be found in the documentation for the individual simulators.
|
||||
|
||||
Select "SIM (SITL)" as the receiver and set up a joystick in the simulator.
|
||||
|
||||
*Not available with INAV-X-Plane-HITL plugin.*
|
||||
|
||||
### Serial Receiver via USB
|
||||
|
||||
Connect a serial receiver (e.g. SBUS) to the PC via a UART/USB adapter. Configure the receiver in the Configurator as usual.
|
||||
- Connect a serial receiver to the PC via a USB-to-serial adapter
|
||||
- Configure the receiver in the SITL as usual
|
||||
- While starting SITL from configurator, enable "Serial receiver" option
|
||||
|
||||
The Configurator offers a built-in option for forwarding the serial data to the SITL TCP port, if SITL is started manually the following option can be used:
|
||||
The SITL offers a built-in option for forwarding the host's serial port to the SITL UART.
|
||||
|
||||
The connection can then be established with a programme that forwards the serial data unaltered to TCP, e.g. with the Python script tcp_serial_redirect.py (https://github.com/Scavanger/TCP-Serial-Redirect)
|
||||
If necessary, please download the required runtime environment from https://www.python.org/.
|
||||
Please use the linked version, which has a smaller buffer, otherwise the control response is relatively slow.
|
||||
Please note that 100000(SBUS) and 420000(CRSF) are non-standart baud rates which may not be supported by some USB-to-serial adapters. FDTI and CH340 should work. CP2102/9 does not work.
|
||||
|
||||
### Example SBUS:
|
||||
For this you need a FT232 module. With FT-Prog (https://ftdichip.com/utilities/) the signals can be inverted: Devices->Scan and Parse, then Hardware Specific -> Invert RS232 Signals -> Invert RXD.
|
||||
|
||||
#### Example SBUS:
|
||||
For this you need a USB-to-serial adapter, receiver with inverter, or receiver which can output inverted SBUS (normal UART).
|
||||
|
||||
SBUS protocol is inverted UART.
|
||||
|
||||
Receiver's SBUS output should be connected to the USB-to-serial adapter's RX pin (via inverter).
|
||||
|
||||
With FT-Prog (https://ftdichip.com/utilities/) the signal can be inverted by adapter: Devices->Scan and Parse, then Hardware Specific -> Invert RS232 Signals -> Invert RXD.
|
||||
|
||||

|
||||
|
||||
For SBUS, the command line arguments of the python script are:
|
||||
```python tcp_serial_redirect.py --parity E --stopbits 2 -c 127.0.0.1:[INAV-UART-PORT] COMXX 100000```
|
||||

|
||||
|
||||
### Telemtry
|
||||
### Telemetry
|
||||
In the SITL configuration, enable serial receiver on some port and configure receiver type "Serial", "SBUS".
|
||||
|
||||
LTM and MAVLink telemetry are supported, either as a discrete function or shared with MSP.
|
||||
#### Example CRSF:
|
||||
|
||||
On receiver side, CRSF is normal UART.
|
||||
|
||||
Connect receiver's RX/TX pins (and GND, 5V of course) to USB-To-Serial adapter's TX/RX pins (RX to TX, TX to RX).
|
||||
|
||||

|
||||
|
||||
In the SITL configuration, enable serial receiver on some port and configure receiver type "Serial", "CRSF".
|
||||
|
||||
### Proxy Flight controller
|
||||
|
||||
The last, but probably the most easiest way to connect receiver to the SITL, is to use any inav/betaflight Flight controler as proxy.
|
||||
|
||||
Connect receiver of any type to FC and configure FC to the point where channels are correctly updated in the "Receiver" tab. Inav and Betaflight are supported.
|
||||
|
||||
You also can use your plane/quad ( if receiver is powered from USB).
|
||||
|
||||

|
||||
|
||||
In the SITL configuration, select "Receiver type: SIM" regardles of the kind of receiver used.
|
||||
|
||||
RX Telemetry via a return channel through the receiver is not yet supported by SITL.
|
||||
|
||||
## OSD
|
||||
For the OSD the program INAV-Sim-OSD is available: https://github.com/Scavanger/INAV-SIM-OSD.
|
||||
|
@ -91,6 +134,8 @@ For this, activate MSP-Displayport on a UART/TCP port and connect to the corresp
|
|||
|
||||
Note: INAV-Sim-OSD only works if the simulator is in window mode.
|
||||
|
||||
*With INAV-X-Plane-HITL plugin, OSD is supported natively.*
|
||||
|
||||
## Command line
|
||||
|
||||
The command line options are only necessary if the SITL executable is started by hand.
|
||||
|
@ -103,7 +148,7 @@ If SITL is started without command line options, only a serial MSP / CLI connect
|
|||
|
||||
```--path``` Path and file name to config file. If not present, eeprom.bin in the current directory is used. Example: ```C:\INAV_SITL\flying-wing.bin```, ```/home/user/sitl-eeproms/test-eeprom.bin```.
|
||||
|
||||
```--sim=[sim]``` Select the simulator. xp = X-Plane, rf = RealFlight. Example: ```--sim=xp```
|
||||
```--sim=[sim]``` Select the simulator. xp = X-Plane, rf = RealFlight. Example: ```--sim=xp```. If not specified, configurator-only mode is started. Omit for usage with INAV-X-Plane-HITL plugin.
|
||||
|
||||
```--simip=[ip]``` Hostname or IP address of the simulator, if you specify a simulator with "--sim" and omit this option IPv4 localhost (`127.0.0.1`) will be used. Example: ```--simip=172.65.21.15```, ```--simip acme-sims.org```, ```--sim ::1```.
|
||||
|
||||
|
@ -118,6 +163,18 @@ To assign motor1 to virtual receiver channel 1, servo 1 to channel 2, and servo2
|
|||
```--chanmap:M01-01,S01-02,S02-03```
|
||||
Please also read the documentation of the individual simulators.
|
||||
|
||||
```--serialport``` Use serial receiver or proxy FC connected to host's serial port, f.e. ```--serialportCOM5``` or ```--serialportdev/ttyACM3```
|
||||
|
||||
```--serialuart``` Map serial receiver to SITL UART, f.e. ```--serialuart=3``` for UART3. Omit if using ```--fcproxy```.
|
||||
|
||||
```--baudrate``` Serial receiver baudrate (default: 115200)
|
||||
|
||||
```--stopbits=[None|One|Two]``` Serial receiver stopbits (default: One)
|
||||
|
||||
```--parity=[Even|None|Odd]``` Serial receiver parity (default: None)
|
||||
|
||||
```--fcproxy``` Use inav/betaflight FC as a proxy for serial receiver.
|
||||
|
||||
```--help``` Displays help for the command line options.
|
||||
|
||||
For options that take an argument, either form `--flag=value` or `--flag value` may be used.
|
||||
|
@ -125,46 +182,13 @@ For options that take an argument, either form `--flag=value` or `--flag value`
|
|||
## Running SITL
|
||||
It is recommended to start the tools in the following order:
|
||||
1. Simulator, aircraft should be ready for take-off
|
||||
2. INAV-SITL
|
||||
2. SITL
|
||||
3. OSD
|
||||
4. serial redirect for RC input
|
||||
|
||||
## Compile
|
||||
For INav-X-Plane-HITL plugin:
|
||||
1. SITL (Run in configurator-only mode)
|
||||
2. X-Plane
|
||||
|
||||
### Linux and FreeBSD:
|
||||
Almost like normal, ruby, cmake and make are also required.
|
||||
With cmake, the option "-DSITL=ON" must be specified.
|
||||
# #Forwarding serial data for other UART
|
||||
|
||||
```
|
||||
mkdir build_SITL
|
||||
cd build_SITL
|
||||
cmake -DSITL=ON ..
|
||||
make
|
||||
```
|
||||
|
||||
### Windows:
|
||||
Compile under cygwin, then as in Linux.
|
||||
Copy cygwin1.dll into the directory, or include cygwin's /bin/ directory in the environment variable PATH.
|
||||
|
||||
If the build fails (segfault, possibly out of memory), adding `-DCMAKE_BUILD_TYPE=MinRelSize` to the `cmake` command may help.
|
||||
|
||||
#### Build manager
|
||||
|
||||
`ninja` may also be used (parallel builds without `-j $(nproc)`):
|
||||
|
||||
```
|
||||
cmake -GNinja -DSITL=ON ..
|
||||
ninja
|
||||
```
|
||||
|
||||
### Compiler requirements
|
||||
|
||||
* Modern GCC. Must be a *real* GCC, macOS faking it with clang will not work. GCC 10 to GCC 13 are known to work.
|
||||
* Unix sockets networking. Cygwin is required on Windows (vice `winsock`).
|
||||
* Pthreads
|
||||
|
||||
## Supported environments
|
||||
|
||||
* Linux on x86_64, ia-32, Aarch64 (e.g. Rpi4), RISCV64 (e.g. VisionFive2)
|
||||
* Windows on x86_64
|
||||
* FreeBSD (x86_64 at least).
|
||||
Other UARTs can then be mapped to host's serial port using external tool, which can be found in directories ```inav-configurator\resources\sitl\linux\Ser2TCP```, ```inav-configurator\resources\sitl\windows\Ser2TCP.exe```
|
||||
|
|
BIN
docs/SITL/assets/serial_receiver_crsf.png
Normal file
BIN
docs/SITL/assets/serial_receiver_crsf.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 6.8 KiB |
BIN
docs/SITL/assets/serial_receiver_proxy.png
Normal file
BIN
docs/SITL/assets/serial_receiver_proxy.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 6.9 KiB |
BIN
docs/SITL/assets/serial_receiver_sbus.png
Normal file
BIN
docs/SITL/assets/serial_receiver_sbus.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 6.6 KiB |
|
@ -6,7 +6,7 @@ As many can attest, multirotors and RC models in general can be very dangerous,
|
|||
|
||||
## Before Installing
|
||||
|
||||
Please consult the [Cli](Cli.md), [Controls](Controls.md), [Failsafe](Failsafe.md) and [Modes](Modes.md)
|
||||
Please consult the [Cli](Cli.md), [Controls](Controls.md), [Failsafe](Failsafe.md) and [Modes](https://github.com/iNavFlight/inav/wiki/Modes)
|
||||
pages for further important information.
|
||||
|
||||
You are highly advised to use the Receiver tab in the INAV Configurator, making sure your Rx channel
|
||||
|
|
BIN
docs/Screenshots/ADSB_TTSC01_settings.png
Normal file
BIN
docs/Screenshots/ADSB_TTSC01_settings.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 94 KiB |
BIN
docs/Screenshots/programming_disable_gps_sensor_fix.png
Normal file
BIN
docs/Screenshots/programming_disable_gps_sensor_fix.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 15 KiB |
56
docs/Serial Gimbal.md
Normal file
56
docs/Serial Gimbal.md
Normal file
|
@ -0,0 +1,56 @@
|
|||
# Serial Gimbal
|
||||
INAV 8.0 introduces support for serial Gimbals. Currently, it is compatible with the protocol used by the Walksnail GM series gimbals.
|
||||
|
||||
While these gimbals also support PWM as input, using the Serial protocol gives it more flexibility and saves up to 4 PWM channels. The downside of the Serial protocol vs PWM input is that you don't have access to the full power of INAV's mixers. The main advantage is that you gain easy control of gimbal functions using INAV's modes.
|
||||
|
||||
# Axis Input
|
||||
The Serial Gimbal supports 2 differents inputs.
|
||||
|
||||
## PWM Channels
|
||||
This is the simplest way to control the Gimbal, as you can use your radio mixer and sliders to Control the gimbal by assigning RC channels to functions in the ```Configuration``` tab. You can control all 3 gimbal axis and unlike the raw PWM input, gimbal modes are controlled by INAV modes and you can control roll channel as well, instead of wiring 4 servo outputs. If an rc channel is set to 0, that input will be ignore and will be equivalent to a centered RC channel. So, if you setup the serial gimbal and don't assign any rc channels, it will stay centered, with default sensitivity and will obey the Gimbal MODES setup in the Modes tab.
|
||||
|
||||
## Headtracker Input
|
||||
Headtracker input is only used when you have a Headtracker device configured and the ```Gimbal Headtracker``` mode is active.
|
||||
A Headtracker device is a device that transmits headtracker information by a side channel, instead of relying on your rc link.
|
||||
|
||||
In head tracker mode, the Serial Gimbal will ignore the axis rc channel inputs and replace it with the inputs coming from the Headtracker device.
|
||||
|
||||
# Gimbal Modes
|
||||
## No Gimbal mode selected
|
||||
Like ACRO is the default mode for flight modes, the Gimbal will default to ```FPV Mode``` or ```Follow Mode``` when no mode is selected. The gimbal will try to stablized the footage and will follow the aircraft pitch, roll and yaw movements and use user inputs to point the camera where the user wants.
|
||||
|
||||
## Gimbal Center
|
||||
This locks the gimbal camera to the center position and ignores any user input. Useful to reset the camera if you loose orientation.
|
||||
|
||||
## Gimbal Headtracker
|
||||
Switches inputs to the configured Headtracker device. If no device is configured it will behave like Gimbal Center.
|
||||
|
||||
## Gimbal Level Tilt
|
||||
This mode locks the camera tilt (pitch axis) and keeps it level with the horizon. Pitching the aircraft up and down, will move the camera so it stays pointing at the horizon. It can be combined with ```Gimbal Level Roll```.
|
||||
|
||||
## Gimbal Level Roll
|
||||
This mode locks the camera roll and keeps it level with the horizon. Rolling the aircraft will move the camera so it stays level with the horizon. It can be combined with ```Gimbal Level Tilt```.
|
||||
|
||||
# Advanced settings
|
||||
The gimbal also supports some advanced settings not exposed in the configurator.
|
||||
|
||||
## Gimbal Trim
|
||||
You can set a trim setting for the gimbal, the idea is that it will shift the notion of center of the gimbal, like a trim and let you setup a fixed camera up tilt, like you would have in a traditional fpv quad setup.
|
||||
|
||||
```
|
||||
gimbal_pan_trim = 0
|
||||
Allowed range: -500 - 500
|
||||
|
||||
gimbal_tilt_trim = 0
|
||||
Allowed range: -500 - 500
|
||||
|
||||
gimbal_roll_trim = 0
|
||||
Allowed range: -500 - 500
|
||||
```
|
||||
|
||||
## Gimbal and Headtracker on a single uart
|
||||
As INAV does not process any inputs from the Walksnail Gimbal, it is possible to share the uart with the Walksnail Headtracking output by connect the fc TX to the gimbal and RX to receive the headtracker input.
|
||||
```
|
||||
gimbal_serial_single_uart = OFF
|
||||
Allowed values: OFF, ON
|
||||
```
|
816
docs/Settings.md
816
docs/Settings.md
File diff suppressed because it is too large
Load diff
|
@ -102,17 +102,21 @@ The following sensors are transmitted
|
|||
* **VSpd** : vertical speed, unit is cm/s.
|
||||
* **Hdg** : heading, North is 0°, South is 180°.
|
||||
* **AccX,Y,Z** : accelerometer values (not sent if `frsky_pitch_roll = ON`).
|
||||
* **Tmp1** : flight mode, sent as 5 digits. Number is sent as **ABCDE** detailed below. The numbers are additives (for example: if digit C is 6, it means both position hold and altitude hold are active) :
|
||||
* **470** : flight mode, sent as 5 digits. Number is sent as **ABCDE** detailed below. The numbers are additives (for example: if digit C is 6, it means both position hold and altitude hold are active) :
|
||||
* **A** : 1 = flaperon mode, 2 = auto tune mode, 4 = failsafe mode
|
||||
* **B** : 1 = return to home, 2 = waypoint mode, 4 = headfree mode
|
||||
* **C** : 1 = heading hold, 2 = altitude hold, 4 = position hold
|
||||
* **D** : 1 = angle mode, 2 = horizon mode, 4 = passthru mode
|
||||
* **E** : 1 = ok to arm, 2 = arming is prevented, 4 = armed
|
||||
* **Tmp2** : GPS lock status, accuracy, home reset trigger, and number of satellites. Number is sent as **ABCD** detailed below. Typical minimum GPS 3D lock value is 3906 (GPS locked and home fixed, HDOP highest accuracy, 6 satellites).
|
||||
|
||||
_NOTE_ This sensor used to be **Tmp1**. The ID has been reassigned in INAV 8.0. The old ID of **Tmp1** can still be used, by using `set frsky_use_legacy_gps_mode_sensor_ids = ON`. This is deprecated and will be removed in INAV 10.0. All tools and scripts using the old IDs should be updated to use the new ID.
|
||||
* **480** : GPS lock status, accuracy, home reset trigger, and number of satellites. Number is sent as **ABCD** detailed below. Typical minimum GPS 3D lock value is 3906 (GPS locked and home fixed, HDOP highest accuracy, 6 satellites).
|
||||
* **A** : 1 = GPS fix, 2 = GPS home fix, 4 = home reset (numbers are additive)
|
||||
* **B** : GPS accuracy based on HDOP (0 = lowest to 9 = highest accuracy)
|
||||
* **C** : number of satellites locked (digit C & D are the number of locked satellites)
|
||||
* **D** : number of satellites locked (if 14 satellites are locked, C = 1 & D = 4)
|
||||
|
||||
_NOTE_ This sensor used to be **Tmp2**. The ID has been reassigned in INAV 8.0. The old ID of **Tmp2** can still be used, by using `set frsky_use_legacy_gps_mode_sensor_ids = ON`. This is deprecated and will be removed in INAV 10.0. All tools and scripts using the old IDs should be updated to use the new ID.
|
||||
* **GAlt** : GPS altitude, sea level is zero.
|
||||
* **ASpd** : true air speed, from pitot sensor. This is _Knots * 10_
|
||||
* **A4** : average cell value. Warning : unlike FLVSS and MLVSS sensors, you do not get actual lowest value of a cell, but an average : (total lipo voltage) / (number of cells)
|
||||
|
@ -390,3 +394,21 @@ In configurator set IBUS telemetry and RX on this same port, enable telemetry fe
|
|||
|
||||
Warning:
|
||||
Schematic above work also for connect telemetry only, but not work for connect rx only - will stop FC.
|
||||
|
||||
|
||||
## Futaba SBUS2 telemetry
|
||||
|
||||
SBUS2 telemetry requires a single connection from the TX pin of a bidirectional serial port to the SBUS2 pin on a Futaba T-FHSS or FASSTest telemetry receiver. (tested T16IZ radio and R7108SB and R3204SB receivers)
|
||||
|
||||
It shares 1 line for both TX and RX, the rx pin cannot be used for other serial port stuff.
|
||||
It runs at a fixed baud rate of 100000, so it needs a hardware uart capable of inverted signals. It is not available on F4 mcus.
|
||||
|
||||
```
|
||||
_______
|
||||
/ \ /-------------\
|
||||
| STM32 |-->UART TX-->[Bi-directional @ 100000 baud]-->| Futaba RX |
|
||||
| uC |- UART RX--x[not connected] | SBUS2 port |
|
||||
\_______/ \-------------/
|
||||
```
|
||||
|
||||
For more information and sensor slot numbering, refer to [SBUS2 Documentation](SBUS2_telemetry.md)
|
|
@ -49,14 +49,19 @@ With the board connected and in bootloader mode (reset it by sending the charact
|
|||
* Choose Options > List All Devices
|
||||
* Select `STM32 BOOTLOADER` in the device list
|
||||
* Choose `WinUSB (v6.x.x.x)` in the right hand box
|
||||
|
||||
|
||||

|
||||
|
||||
* Click Replace Driver
|
||||
* Restart the Configurator (make sure it is completely closed, logout and login if unsure)
|
||||
* Now the DFU device should be seen by Configurator
|
||||
|
||||
## While Using USB-C cables
|
||||
|
||||
* If you are using a device with only USB-C ports such as a Mac-OS device, you will need a dongle.
|
||||
* A USB-C to USB-C cable is identical on both ends and thus requires extra hardware to let them be auto detected as devices instead of hosts.
|
||||
* Using either a hub with USB-A ports, or a USB-A to C cable or dongle is usually the easiest way to get a working connection but an USB-OTG adapter also works.
|
||||
|
||||
## Using `dfu-util`
|
||||
|
||||
`dfu-util` is a command line tool to flash ARM devices via DFU. It is available via the package manager on most Linux systems or from [source forge](http://sourceforge.net/p/dfu-util).
|
||||
|
|
|
@ -186,7 +186,8 @@ Add new servo mixer rules, and select 'Mixer Transition' in input. Set the weigh
|
|||
## Motor 'Transition Mixing': Dedicated forward motor configuration
|
||||
In motor mixer set:
|
||||
- -2.0 < throttle < -1.0: The motor will spin regardless of the radio's throttle position at a speed of `abs(throttle) - 1` multiplied by throttle range only when Mixer Transition is activated.
|
||||
|
||||
- Airmode type should be set to "STICK_CENTER". Airmode type must NOT be set to "THROTTLE_THRESHOLD". If set to throttle threshold the (-) motor will spin till throttle threshold is passed.
|
||||
|
||||

|
||||
|
||||
## TailSitter 'Transition Mixing':
|
||||
|
@ -233,4 +234,4 @@ If you set `mixer_automated_switch` to `OFF` for all mixer profiles (the default
|
|||
2. In addition to 1. Add a little yaw mixing(about 0.2) in tilt motors.
|
||||
- There will be a time window that tilting motors is providing up lift but rear motor isn't. Result in a sudden pitch raise on the entering of the mode. Use the max speed or faster speed in tiling servo to reduce the time window. OR lower the throttle on the entering of the FW mode to mitigate the effect.
|
||||
## Dedicated forward motor
|
||||
- Easiest way to setup a vtol. and efficiency can be improved by using different motor/prop for hover and forward flight
|
||||
- Easiest way to setup a vtol. and efficiency can be improved by using different motor/prop for hover and forward flight
|
||||
|
|
BIN
docs/assets/images/KAKUTEH7WING-wiring-diagram.webp
Normal file
BIN
docs/assets/images/KAKUTEH7WING-wiring-diagram.webp
Normal file
Binary file not shown.
After Width: | Height: | Size: 286 KiB |
10
docs/boards/KAKUTEH7WING.md
Normal file
10
docs/boards/KAKUTEH7WING.md
Normal file
|
@ -0,0 +1,10 @@
|
|||
# Board - [KAKUTEH7WING](https://holybro.com/products/kakute-h743-wing)
|
||||
|
||||
[manufacturer manual](https://cdn.shopify.com/s/files/1/0604/5905/7341/files/Holybro_KakuteH743-Wing_Manual_v1.0_C.pdf?v=1693393206)
|
||||
|
||||
Note that this board has two i2c plugs.
|
||||
The six-pin plug should be used for GPS and compass.
|
||||
The 4-pin plug should be used for other i2c sesors such as i2c pitot (airspeed sensor), rangefinder, and external
|
||||
temperature sensors.
|
||||
|
||||

|
|
@ -1,6 +1,6 @@
|
|||
# SpeedyBee F405 V3
|
||||
|
||||
> Notice: At the moment, DSHOT is not supported on SpeedyBe F405 V3. Use Multishot instead
|
||||
> Notice: DSHOT on SpeedyBe F405 V3 requires INAV 7.0.0 or later. If you are using an older version, use MULTISHOT instead.
|
||||
|
||||
> Notice: The analog OSD and the SD card (blackbox) share the same SPI bus, which can cause problems when trying to use analog OSD and blackbox at the same time.
|
||||
|
||||
|
|
|
@ -566,7 +566,6 @@ The log end marker is an optional Event ("E") frame of type 0xFF whose payload i
|
|||
<li> Sticks</li>
|
||||
<li> Switch_3D</li>
|
||||
<li> Switch</li>
|
||||
<li> Killswitch</li>
|
||||
<li> Failsafe</li>
|
||||
<li> Navigation</li>
|
||||
</ol>
|
||||
|
|
39
docs/development/Building SITL.md
Normal file
39
docs/development/Building SITL.md
Normal file
|
@ -0,0 +1,39 @@
|
|||
## Building SITL
|
||||
|
||||
### Linux and FreeBSD:
|
||||
Almost like normal, ruby, cmake and make are also required.
|
||||
With cmake, the option "-DSITL=ON" must be specified.
|
||||
|
||||
```
|
||||
mkdir build_SITL
|
||||
cd build_SITL
|
||||
cmake -DSITL=ON ..
|
||||
make
|
||||
```
|
||||
|
||||
### Windows:
|
||||
Compile under cygwin, then as in Linux.
|
||||
Copy cygwin1.dll into the directory, or include cygwin's /bin/ directory in the environment variable PATH.
|
||||
|
||||
If the build fails (segfault, possibly out of memory), adding `-DCMAKE_BUILD_TYPE=MinRelSize` to the `cmake` command may help.
|
||||
|
||||
#### Build manager
|
||||
|
||||
`ninja` may also be used (parallel builds without `-j $(nproc)`):
|
||||
|
||||
```
|
||||
cmake -GNinja -DSITL=ON ..
|
||||
ninja
|
||||
```
|
||||
|
||||
### Compiler requirements
|
||||
|
||||
* Modern GCC. Must be a *real* GCC, macOS faking it with clang will not work. GCC 10 to GCC 13 are known to work.
|
||||
* Unix sockets networking. Cygwin is required on Windows (vice `winsock`).
|
||||
* Pthreads
|
||||
|
||||
## Supported environments
|
||||
|
||||
* Linux on x86_64, ia-32, Aarch64 (e.g. Rpi4), RISCV64 (e.g. VisionFive2)
|
||||
* Windows on x86_64
|
||||
* FreeBSD (x86_64 at least).
|
|
@ -1,5 +1,7 @@
|
|||
# Building with Docker
|
||||
|
||||
> **On Windows building with this method is not advised and should be used only if Windows Linux Subsystem can not be used. In all other cases all Windows users should be using Linux Subsystem (WSL) instead**
|
||||
|
||||
Building with [Docker](https://www.docker.com/) is remarkably easy: an isolated container will hold all the needed compilation tools so that they won't interfere with your system and you won't need to install and manage them by yourself. You'll only need to have Docker itself [installed](https://docs.docker.com/install/).
|
||||
|
||||
The first time that you'll run a build it will take a little more time than following executions since it will be building its base image first. Once this initial process is completed, the firmware will be always built immediately.
|
||||
|
|
19
docs/development/Building in Gitpod.md
Normal file
19
docs/development/Building in Gitpod.md
Normal file
|
@ -0,0 +1,19 @@
|
|||
# Building in Gitpod
|
||||
|
||||
Gitpod offers an online build environment for building INAV targets.
|
||||
## Setting up the environment and building targets
|
||||
|
||||
1. Go to https://gitpod.io/new
|
||||
1. Paste `https://github.com/iNavFlight/inav/tree/[version]` into the field called "Select a repository".
|
||||
1. Ensure that you substitute [version] (e.g. 7.1.0) with the version number of INAV that you want to build.
|
||||
1. Cick on the link that shows in the drop down and Gitpod will atomatically selects the adequate Editor and Browser.
|
||||
1. Leave the other fields as default and click "Continue". Your build environment will be created.
|
||||
1. At the bottom of the page, you will see a command line. Type `make [TARGET]` and wait for the target to be built.
|
||||
1. Once the build has finished, navigate to the build folder using `cd build`.
|
||||
1. Once in the folder, run `objcopy -O ihex -R .eeprom [TARGET].elf [TARGET].hex` to convert the `.elf` file to a `.hex` file.
|
||||
1. Your new target `.hex` binary will be located in a folder called `bin`, which can be found at the top left of the page.
|
||||
|
||||
|
||||
NOTE: You can use this method to build your forks as well. Just paste in the link to your fork and follow the rest of the steps.
|
||||
|
||||
You are done!
|
|
@ -1,5 +1,7 @@
|
|||
# Building with Vagrant
|
||||
|
||||
> **On Windows building with this method is not advised and should be used only if Windows Linux Subsystem can not be used. In all other cases all Windows users should be using Linux Subsystem (WSL) instead**
|
||||
|
||||
Setting up build environment with Vagrant is remarkably simple, but you still need to have some basic knowlage of your OS.
|
||||
|
||||
## Installing Vagrant
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
# Building in Windows 10 with Linux subsystem [Recommended]
|
||||
# Building in Windows 10/11 with Linux subsystem (WSL) [Recommended]
|
||||
|
||||
Linux subsystem for Windows 10 is probably the simplest way of building INAV under Windows 10.
|
||||
Linux subsystem for Windows (WSL) 10/11 is probably the simplest way of building INAV under Windows.
|
||||
|
||||
## Setting up the environment
|
||||
|
||||
|
@ -9,7 +9,6 @@ run `windows features`
|
|||
enable `windows subsytem for linux`
|
||||
reboot
|
||||
|
||||
|
||||
Install Ubuntu:
|
||||
1. Go to Microsoft store https://www.microsoft.com/en-gb/store/b/home
|
||||
1. Search and install most recent Ubuntu LTS version
|
||||
|
@ -56,12 +55,12 @@ You can fix this with by remounting the drive using the following commands
|
|||
1. `sudo umount /mnt/c`
|
||||
2. `sudo mount -t drvfs C: /mnt/c -o metadata`
|
||||
|
||||
## Building (example):
|
||||
## Building with Make (example):
|
||||
|
||||
For detailed build instrusctions see [Building in Linux](Building%20in%20Linux.md)
|
||||
For detailed build instructions see [Building in Linux](Building%20in%20Linux.md)
|
||||
|
||||
Launch Ubuntu:
|
||||
Click Windows Start button then scroll and lauch "Ubuntu"
|
||||
Click Windows Start button then scroll and launch "Ubuntu"
|
||||
|
||||
Building from Ubuntu command line
|
||||
|
||||
|
@ -80,6 +79,39 @@ cd build
|
|||
make MATEKF722
|
||||
```
|
||||
|
||||
## Building with Ninja (example):
|
||||
|
||||
[Ninja](https://ninja-build.org/) is a popular cross-platform tool. It is both lightweight and executes parallel builds by default. It is advantageous to use this over the old _make_ method. There are detailed instructions for building with Ninja in [Building in Linux](Building%20in%20Linux.md#building-with-ninja).
|
||||
|
||||
Launch Ubuntu:
|
||||
Click Windows Start button. Then scroll and launch **Ubuntu**.
|
||||
|
||||
> [!TIP]
|
||||
> Before using Ninja, you will need to install it. From the Ubuntu command prompt type `sudo apt-get install ninja-build -y` and press enter.
|
||||
|
||||
Building from the command line:
|
||||
|
||||
First, change to the INAV directory with
|
||||
```cd /mnt/c/inav```
|
||||
|
||||
Before building, you will need to prepare the build environment. You only need to do this once, unless you reinstall WSL or cmake.
|
||||
|
||||
```
|
||||
mkdir build
|
||||
cd build
|
||||
cmake -GNinja ..
|
||||
```
|
||||
|
||||
From then on, you can build your target by calling the following from inside the build directory.
|
||||
```
|
||||
ninja MATEKF722
|
||||
```
|
||||
|
||||
If you want to build multiple targets. You can use:
|
||||
```
|
||||
ninja MATEKF722 MATEKF405SE SPEEDYBEEF405
|
||||
```
|
||||
|
||||
## Updating the documents
|
||||
```
|
||||
cd /mnt/c/inav
|
||||
|
|
|
@ -1,4 +1,7 @@
|
|||
# Building in Windows with MSYS2
|
||||
|
||||
> **Building with this method is not advised and should be used only if Windows Linux Subsystem can not be used. In all other cases all Windows users should be using Linux Subsystem (WSL) instead**
|
||||
|
||||
- This environment does not require installing WSL, which may not be available or would get in the way of other virtualization and/or anti-cheat software
|
||||
- It is also much faster to install and get set up because of its small size(~3.65 GB total after building hex file as of 6.0.0)
|
||||
## Setting up the environment
|
||||
|
|
74
docs/development/Converting Betaflight Targets.md
Normal file
74
docs/development/Converting Betaflight Targets.md
Normal file
|
@ -0,0 +1,74 @@
|
|||
If your flight controller does not have an official INAV target, it is possible to use src/utils/bf2inav.py script to generate a good starting point for an unofficial INAV target.
|
||||
|
||||
This script can read the config.h from [Betaflight's target configuration repository](https://github.com/betaflight/config) and it currently supports STM32F405, STM32F722, STM32F745, STM32H743 and AT32F435 targets.
|
||||
Locate your Flight Controller target config.h in BetaFlight's repo, eg.: [config.h](https://github.com/betaflight/config/blob/master/configs/BETAFPVF405/config.h), for BETAFPVF435 target.
|
||||
|
||||
It is also advisable to record the output of the timer command from BetaFlight, as it will provide useful information on `timer` usage that can be used to adjust the generated target later.
|
||||
|
||||
```
|
||||
# timer
|
||||
timer B08 AF3
|
||||
# pin B08: TIM10 CH1 (AF3)
|
||||
timer C08 AF3
|
||||
# pin C08: TIM8 CH3 (AF3)
|
||||
timer B00 AF2
|
||||
# pin B00: TIM3 CH3 (AF2)
|
||||
timer B01 AF2
|
||||
# pin B01: TIM3 CH4 (AF2)
|
||||
timer A03 AF1
|
||||
# pin A03: TIM2 CH4 (AF1)
|
||||
timer A02 AF1
|
||||
# pin A02: TIM2 CH3 (AF1)
|
||||
timer B06 AF2
|
||||
# pin B06: TIM4 CH1 (AF2)
|
||||
timer A08 AF1
|
||||
# pin A08: TIM1 CH1 (AF1)
|
||||
timer A09 AF1
|
||||
# pin A09: TIM1 CH2 (AF1)
|
||||
timer A10 AF1
|
||||
# pin A10: TIM1 CH3 (AF1)
|
||||
```
|
||||
In the above example, `pin B08: TIM10 CH1 (AF3)` means that pind to CH1. This information can be used to fix the generated timer assigned to match BetaFlight's allocation by editing the `target.c` file generated by the `bf2inav.py` script.
|
||||
|
||||
|
||||
Using the BETAFPVF405 target mentioned above, to create the target now we need to:
|
||||
|
||||
1. Download INAV source code and be able to build
|
||||
2. Download the config.h from BetaFlight repository
|
||||
3. Create a target folder that will be used as the output folder for the `bf2inav.py` script, eg: `inav/src/main/targets/BETAFPVF405`
|
||||
4. Navigate to the script folder in `inav/src/utils/`
|
||||
5. `python3 ./bf2inav.py -i config.h -o ../main/target/BETAFPVF405/`
|
||||
6. Edit generated `target.c` and chose the correct timer definitions to match Betaflight's timer definitions.
|
||||
```
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
//DEF_TIM(TIM8, CH2N, PB0, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
//DEF_TIM(TIM1, CH2N, PB0, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
//DEF_TIM(TIM8, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
//DEF_TIM(TIM1, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
|
||||
//DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
//DEF_TIM(TIM9, CH2, PA3, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
|
||||
//DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
//DEF_TIM(TIM9, CH1, PA2, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
//DEF_TIM(TIM3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
|
||||
//DEF_TIM(TIM3, CH1, PB4, TIM_USE_BEEPER, 0, 0),
|
||||
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0),
|
||||
|
||||
};
|
||||
```
|
||||
In this particular example, PA3, PA2 were changed to match Betaflight's mapping, and the timer PB4 was disabled, due to a timer conflict. Normal channels are prefered over N channels (CH1, over CH1N) or C channels in AT32 architectures.
|
||||
7. Now update yout build scripts by running `cmake` and build the target you just created. The target name can be checked in the generated `CMakeLists.txt`, but should match the Betaflight target name.
|
||||
|
||||
For information on how to build INAV, check the documents in the [docs/development](https://github.com/iNavFlight/inav/tree/master/docs/development) folder.
|
|
@ -1,4 +1,8 @@
|
|||
# Building in windows light [Deprecated]
|
||||
|
||||
> **Building with this method is deprecated and not advised. All Windows users should be using
|
||||
Linux Subsystem (WSL) instead**
|
||||
|
||||
no cygwin and no path changes
|
||||
|
||||
## Install Git for windows
|
|
@ -98,10 +98,13 @@ LOG_BUF_DEBUG(TEMPERATURE, &tstruct, sizeof(tstruct));
|
|||
|
||||
Log messages are transmitted through the `FUNCTION_LOG` serial port as MSP messages (`MSP_DEBUGMSG`). It is possible to use any serial terminal to display these messages, however it is advisable to use an application that understands `MSP_DEBUGMSG` in order to maintain readability (in a raw serial terminal the MSP message envelope may result in the display of strange characters). `MSP_DEBUGMSG` aware applications include:
|
||||
|
||||
* [msp-tool](https://github.com/fiam/msp-tool)
|
||||
* [mwp](https://github.com/stronnag/mwptools)
|
||||
* [dbg-tool](https://github.com/stronnag/mwptools)
|
||||
* [dbg-tool](https://codeberg.org/stronnag/dbg-tool)
|
||||
* [INAV Configurator](https://github.com/iNavFlight/inav-configurator)
|
||||
* [mwp](https://github.com/stronnag/mwptools)
|
||||
|
||||
In addtion:
|
||||
|
||||
* [msp-tool](https://github.com/fiam/msp-tool) is obsolete and has limited OS support.
|
||||
|
||||
For example, with the final lines of `src/main/fc/fc_init.c` set to:
|
||||
|
||||
|
@ -121,10 +124,16 @@ set log_topics = 4294967295
|
|||
The output will be formatted as follows:
|
||||
|
||||
```
|
||||
# msp-tool
|
||||
[DEBUG] [ 3.967] Init is complete
|
||||
# dbg-tool
|
||||
[dbg-tool] 12:46:49.909079 DBG: [ 3.967] Init is complete
|
||||
|
||||
# mwp (stderr log file)
|
||||
2020-02-02T19:09:02+0000 DEBUG:[ 3.968] Init is complete
|
||||
|
||||
# msp-tool
|
||||
[DEBUG] [ 3.967] Init is complete
|
||||
```
|
||||
|
||||
The numeric value in square brackets is the FC uptime in seconds.
|
||||
For the Configurator, debug messages are shown in the developer console log.
|
||||
|
||||
Note: The numeric value in square brackets is the FC uptime in seconds.
|
||||
|
|
|
@ -13,7 +13,16 @@ The format is defined the XSD schema here.
|
|||
* The `mwp` tag was introduced by the eponymous mission planner. Other mission planners may consider that reusing some of the tags (`cx`, `cy` - centre location, `zoom` TMS zoom level, `home-x`, `home-y` - home location) is useful.
|
||||
* `meta` may be used as a synonym for `mwp`.
|
||||
* The `version` tag may be intepreted by mission planners as they see fit. For example, the (obsolete) Android 'ez-gui' application requires '2.3-pre8'. For multi-mission files it is recommended to use another `version`.
|
||||
* the `mwp` / `meta` element may be interleaved with `missionitem` in a multi-mission file to provide mission segment specific home, centre locations and zoom.
|
||||
* The `mwp` / `meta` element may be interleaved with `missionitem` in a multi-mission file to provide mission segment specific home, centre locations and zoom.
|
||||
* The `fwapproach` element defines INAV 7.1.0 and later Autoland parameters for the mission.
|
||||
|
||||
## Validation
|
||||
|
||||
You can check that your files validate using the open source `xmlint` tool.
|
||||
|
||||
```
|
||||
xmllint --schema docs/development/wp_mission_schema/mw-mission.xsd test.mission --noout
|
||||
```
|
||||
|
||||
## Examples
|
||||
|
||||
|
|
|
@ -12,6 +12,7 @@
|
|||
<xs:choice minOccurs="0" maxOccurs="unbounded">
|
||||
<xs:element ref="missionitem"/>
|
||||
<xs:element ref="mwp"/>
|
||||
<xs:element ref="fwapproach"/>
|
||||
</xs:choice>
|
||||
</xs:sequence>
|
||||
</xs:complexType>
|
||||
|
@ -21,6 +22,25 @@
|
|||
<xs:attribute name="value" use="required"/>
|
||||
</xs:complexType>
|
||||
</xs:element>
|
||||
<xs:element name="fwapproach">
|
||||
<xs:complexType>
|
||||
<xs:attribute name="no" use="required" type="xs:integer"/>
|
||||
<xs:attribute name="index" use="required" type="xs:integer"/>
|
||||
<xs:attribute name="approachalt" use="required" type="xs:integer"/>
|
||||
<xs:attribute name="landalt" use="required" type="xs:integer"/>
|
||||
<xs:attribute name="landheading1" use="required" type="xs:integer"/>
|
||||
<xs:attribute name="landheading2" use="required" type="xs:integer"/>
|
||||
<xs:attribute name="approachdirection" use="required">
|
||||
<xs:simpleType>
|
||||
<xs:restriction base="xs:token">
|
||||
<xs:enumeration value="left"/>
|
||||
<xs:enumeration value="right"/>
|
||||
</xs:restriction>
|
||||
</xs:simpleType>
|
||||
</xs:attribute>
|
||||
<xs:attribute name="sealevelref" use="required" type="xs:boolean"/>
|
||||
</xs:complexType>
|
||||
</xs:element>
|
||||
<xs:element name="missionitem">
|
||||
<xs:complexType>
|
||||
<xs:attribute name="action" use="required">
|
||||
|
|
|
@ -23,8 +23,8 @@ New targets are accepted into INAV code if any of the following conditions is sa
|
|||
3. The new target must meet the following minimal requirements:
|
||||
|
||||
* On-board sensors include at least the IMU (gyroscope + accelerometer)
|
||||
* At least 2 hardware serial ports are available with both TX and RX pins
|
||||
* At least 512K of firmware flash memory and at least of 64K of RAM available
|
||||
* At least 3 hardware serial ports are available with both TX and RX pads. 2 serial ports may be accepted if there is an onboard serial RX.
|
||||
* At least 512K of firmware flash memory and at least of 128K of RAM available
|
||||
* At least one I2C bus broken out (SCL and SDA pins) and not shared with other functions
|
||||
|
||||
## New hardware support
|
||||
|
|
|
@ -48,7 +48,7 @@ typedef enum FIRMWARE_VERSION_TYPE
|
|||
} FIRMWARE_VERSION_TYPE;
|
||||
#endif
|
||||
|
||||
/** @brief Flags to report failure cases over the high latency telemtry. */
|
||||
/** @brief Flags to report failure cases over the high latency telemetry. */
|
||||
#ifndef HAVE_ENUM_HL_FAILURE_FLAG
|
||||
#define HAVE_ENUM_HL_FAILURE_FLAG
|
||||
typedef enum HL_FAILURE_FLAG
|
||||
|
|
38
readme.md
38
readme.md
|
@ -1,3 +1,11 @@
|
|||
# INAV 8.0 feature freeze
|
||||
|
||||
It is that time of the year again, and the time for a new INAV release is near!
|
||||
|
||||
The current plan is to have a feature freeze on **15th of November 2024**.
|
||||
|
||||
For a preview of what is comming, have a look at .
|
||||
|
||||
# INAV - navigation capable flight controller
|
||||
|
||||
# F411 PSA
|
||||
|
@ -6,6 +14,22 @@
|
|||
|
||||
> INAV 7 is the last INAV official release available for F411 based flight controllers. The next milestone, INAV 8 will not be available for F411 boards.
|
||||
|
||||
# ICM426xx IMUs PSA
|
||||
|
||||
> The filtering settings for the ICM426xx has changed to match what is used by Ardupilot and Betaflight in INAV 7.1. When upgrading from older versions you may need to recalibrate the Accelerometer and if you are not using INAV's default tune you may also want to check if the tune is still good.
|
||||
|
||||
# M7, M6 and older UBLOX GPS units PSA
|
||||
|
||||
> INAV 8.0 will mark those GPS as deprecated and INAV 9.0.0 will require UBLOX units with Protocol version 15.00 or newer. This means that you need a GPS unit based on UBLOX M8 or newer.
|
||||
|
||||
> If you want to check the protocol version of your unit, it is displayed in INAV's 7.0.0+ status cli command.
|
||||
> INAV 8.0.0 will warn you if your GPS is too old.
|
||||
> ```GPS: HW Version: Unknown Proto: 0.00 Baud: 115200 (UBLOX Proto >= 15.0 required)```
|
||||
|
||||
|
||||
> M8, M9 and M10 GPS are the most common units in use today, are readly available and have similar capabilities.
|
||||
>Mantaining and testing GPS changes across this many UBLOX versions is a challenge and takes a lot of time. Removing the support for older devices will simplify code.
|
||||
|
||||

|
||||
|
||||
# PosHold, Navigation and RTH without compass PSA
|
||||
|
@ -37,8 +61,9 @@ Fly safe, fly smart with INAV 7.1 and a compass by your side!
|
|||
|
||||
## Features
|
||||
|
||||
* Runs on the most popular F4, F7 and H7 flight controllers
|
||||
* MSP Displayport for all the HD Digital FPV systems: DJI, Walksnail and HDZero
|
||||
* Runs on the most popular F4, AT32, F7 and H7 flight controllers
|
||||
* On Screen Display (OSD) - both character and pixel style
|
||||
* DJI OSD integration: all elements, system messages and warnings
|
||||
* Outstanding performance out of the box
|
||||
* Position Hold, Altitude Hold, Return To Home and Waypoint Missions
|
||||
* Excellent support for fixed wing UAVs: airplanes, flying wings
|
||||
|
@ -50,7 +75,6 @@ Fly safe, fly smart with INAV 7.1 and a compass by your side!
|
|||
* SmartAudio and IRC Tramp VTX support
|
||||
* Telemetry: SmartPort, FPort, MAVlink, LTM, CRSF
|
||||
* Multi-color RGB LED Strip support
|
||||
* On Screen Display (OSD) - both character and pixel style
|
||||
* And many more!
|
||||
|
||||
For a list of features, changes and some discussion please review consult the releases [page](https://github.com/iNavFlight/inav/releases) and the documentation.
|
||||
|
@ -118,5 +142,13 @@ Before creating new issues please check to see if there is an existing one, sear
|
|||
|
||||
Please refer to the development section in the [docs/development](https://github.com/iNavFlight/inav/tree/master/docs/development) folder.
|
||||
|
||||
Nightly builds are available for testing on the following links:
|
||||
|
||||
https://github.com/iNavFlight/inav-nightly/releases
|
||||
|
||||
https://github.com/iNavFlight/inav-configurator-nightly/releases
|
||||
|
||||
## INAV Releases
|
||||
https://github.com/iNavFlight/inav/releases
|
||||
|
||||
|
||||
|
|
|
@ -1,3 +1,4 @@
|
|||
|
||||
main_sources(COMMON_SRC
|
||||
main.c
|
||||
|
||||
|
@ -30,6 +31,8 @@ main_sources(COMMON_SRC
|
|||
common/gps_conversion.h
|
||||
common/log.c
|
||||
common/log.h
|
||||
common/lulu.c
|
||||
common/lulu.h
|
||||
common/maths.c
|
||||
common/maths.h
|
||||
common/memory.c
|
||||
|
@ -176,6 +179,10 @@ main_sources(COMMON_SRC
|
|||
drivers/flash_m25p16.h
|
||||
drivers/flash_w25n01g.c
|
||||
drivers/flash_w25n01g.h
|
||||
drivers/gimbal_common.h
|
||||
drivers/gimbal_common.c
|
||||
drivers/headtracker_common.h
|
||||
drivers/headtracker_common.c
|
||||
drivers/io.c
|
||||
drivers/io.h
|
||||
drivers/io_pcf8574.c
|
||||
|
@ -237,6 +244,8 @@ main_sources(COMMON_SRC
|
|||
drivers/rangefinder/rangefinder_us42.h
|
||||
drivers/rangefinder/rangefinder_tof10120_i2c.c
|
||||
drivers/rangefinder/rangefinder_tof10120_i2c.h
|
||||
drivers/rangefinder/rangefinder_teraranger_evo.c
|
||||
drivers/rangefinder/rangefinder_teraranger_evo.h
|
||||
|
||||
drivers/resource.c
|
||||
drivers/resource.h
|
||||
|
@ -343,13 +352,20 @@ main_sources(COMMON_SRC
|
|||
flight/dynamic_lpf.h
|
||||
flight/ez_tune.c
|
||||
flight/ez_tune.h
|
||||
flight/adaptive_filter.c
|
||||
flight/adaptive_filter.h
|
||||
|
||||
io/adsb.c
|
||||
io/beeper.c
|
||||
io/beeper.h
|
||||
io/servo_sbus.c
|
||||
io/servo_sbus.h
|
||||
io/frsky_osd.c
|
||||
io/frsky_osd.h
|
||||
io/gimbal_serial.c
|
||||
io/gimbal_serial.h
|
||||
io/headtracker_msp.c
|
||||
io/headtracker_msp.h
|
||||
io/osd_dji_hd.c
|
||||
io/osd_dji_hd.h
|
||||
io/lights.c
|
||||
|
@ -482,6 +498,8 @@ main_sources(COMMON_SRC
|
|||
io/rangefinder.h
|
||||
io/rangefinder_msp.c
|
||||
io/rangefinder_benewake.c
|
||||
io/rangefinder_usd1_v0.c
|
||||
io/rangefinder_nanoradar.c
|
||||
io/rangefinder_fake.c
|
||||
io/opflow.h
|
||||
io/opflow_cxof.c
|
||||
|
@ -494,8 +512,8 @@ main_sources(COMMON_SRC
|
|||
io/displayport_max7456.h
|
||||
io/displayport_msp.c
|
||||
io/displayport_msp.h
|
||||
io/displayport_msp_bf_compat.c
|
||||
io/displayport_msp_bf_compat.h
|
||||
io/displayport_msp_dji_compat.c
|
||||
io/displayport_msp_dji_compat.h
|
||||
io/displayport_oled.c
|
||||
io/displayport_oled.h
|
||||
io/displayport_msp_osd.c
|
||||
|
@ -558,8 +576,11 @@ main_sources(COMMON_SRC
|
|||
navigation/navigation_pos_estimator_flow.c
|
||||
navigation/navigation_private.h
|
||||
navigation/navigation_rover_boat.c
|
||||
navigation/navigation_geozone.c
|
||||
navigation/sqrt_controller.c
|
||||
navigation/sqrt_controller.h
|
||||
navigation/rth_trackback.c
|
||||
navigation/rth_trackback.h
|
||||
|
||||
sensors/barometer.c
|
||||
sensors/barometer.h
|
||||
|
@ -592,6 +613,10 @@ main_sources(COMMON_SRC
|
|||
telemetry/mavlink.h
|
||||
telemetry/msp_shared.c
|
||||
telemetry/msp_shared.h
|
||||
telemetry/sbus2.c
|
||||
telemetry/sbus2.h
|
||||
telemetry/sbus2_sensors.c
|
||||
telemetry/sbus2_sensors.h
|
||||
telemetry/smartport.c
|
||||
telemetry/smartport.h
|
||||
telemetry/sim.c
|
||||
|
|
|
@ -99,7 +99,7 @@
|
|||
#define BLACKBOX_INVERTED_CARD_DETECTION 0
|
||||
#endif
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 2);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 3);
|
||||
|
||||
PG_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig,
|
||||
.device = DEFAULT_BLACKBOX_DEVICE,
|
||||
|
@ -108,7 +108,8 @@ PG_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig,
|
|||
.invertedCardDetection = BLACKBOX_INVERTED_CARD_DETECTION,
|
||||
.includeFlags = BLACKBOX_FEATURE_NAV_PID | BLACKBOX_FEATURE_NAV_POS |
|
||||
BLACKBOX_FEATURE_MAG | BLACKBOX_FEATURE_ACC | BLACKBOX_FEATURE_ATTITUDE |
|
||||
BLACKBOX_FEATURE_RC_DATA | BLACKBOX_FEATURE_RC_COMMAND | BLACKBOX_FEATURE_MOTORS,
|
||||
BLACKBOX_FEATURE_RC_DATA | BLACKBOX_FEATURE_RC_COMMAND |
|
||||
BLACKBOX_FEATURE_MOTORS | BLACKBOX_FEATURE_SERVOS,
|
||||
);
|
||||
|
||||
void blackboxIncludeFlagSet(uint32_t mask)
|
||||
|
@ -334,22 +335,43 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = {
|
|||
{"motor", 7, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_8)},
|
||||
|
||||
/* servos */
|
||||
{"servo", 0, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)},
|
||||
{"servo", 1, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)},
|
||||
{"servo", 2, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)},
|
||||
{"servo", 3, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)},
|
||||
{"servo", 4, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)},
|
||||
{"servo", 5, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)},
|
||||
{"servo", 6, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)},
|
||||
{"servo", 7, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)},
|
||||
{"servo", 8, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)},
|
||||
{"servo", 9, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)},
|
||||
{"servo", 10, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)},
|
||||
{"servo", 11, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)},
|
||||
{"servo", 12, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)},
|
||||
{"servo", 13, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)},
|
||||
{"servo", 14, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)},
|
||||
{"servo", 15, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)},
|
||||
{"servo", 0, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_1)},
|
||||
{"servo", 1, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_2)},
|
||||
{"servo", 2, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_3)},
|
||||
{"servo", 3, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_4)},
|
||||
{"servo", 4, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_5)},
|
||||
{"servo", 5, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_6)},
|
||||
{"servo", 6, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_7)},
|
||||
{"servo", 7, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_8)},
|
||||
{"servo", 8, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_9)},
|
||||
{"servo", 9, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_10)},
|
||||
{"servo", 10, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_11)},
|
||||
{"servo", 11, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_12)},
|
||||
{"servo", 12, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_13)},
|
||||
{"servo", 13, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_14)},
|
||||
{"servo", 14, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_15)},
|
||||
{"servo", 15, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_16)},
|
||||
{"servo", 16, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_17)},
|
||||
{"servo", 17, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_18)},
|
||||
{"servo", 18, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_19)},
|
||||
{"servo", 19, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_20)},
|
||||
{"servo", 20, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_21)},
|
||||
{"servo", 21, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_22)},
|
||||
{"servo", 22, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_23)},
|
||||
{"servo", 23, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_24)},
|
||||
{"servo", 24, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_25)},
|
||||
{"servo", 25, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_26)},
|
||||
/*
|
||||
{"servo", 26, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_27)},
|
||||
{"servo", 27, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_28)},
|
||||
{"servo", 27, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_29)},
|
||||
{"servo", 28, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_30)},
|
||||
{"servo", 29, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_31)},
|
||||
{"servo", 30, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_32)},
|
||||
{"servo", 31, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_33)},
|
||||
{"servo", 32, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_34)},
|
||||
{"servo", 33, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_35)},
|
||||
*/
|
||||
|
||||
{"navState", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
|
||||
{"navFlags", -1, UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
|
||||
|
@ -402,12 +424,21 @@ static const blackboxSimpleFieldDefinition_t blackboxGpsHFields[] = {
|
|||
|
||||
// Rarely-updated fields
|
||||
static const blackboxSimpleFieldDefinition_t blackboxSlowFields[] = {
|
||||
/* "flightModeFlags" renamed internally to more correct ref of rcModeFlags, since it logs rc boxmode selections,
|
||||
* but name kept for external compatibility reasons.
|
||||
* "activeFlightModeFlags" logs actual active flight modes rather than rc boxmodes.
|
||||
* 'active' should at least distinguish it from the existing "flightModeFlags" */
|
||||
|
||||
{"activeWpNumber", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
{"flightModeFlags", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
{"flightModeFlags2", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
{"activeFlightModeFlags", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
{"stateFlags", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
|
||||
{"failsafePhase", -1, UNSIGNED, PREDICT(0), ENCODING(TAG2_3S32)},
|
||||
{"rxSignalReceived", -1, UNSIGNED, PREDICT(0), ENCODING(TAG2_3S32)},
|
||||
{"rxFlightChannelsValid", -1, UNSIGNED, PREDICT(0), ENCODING(TAG2_3S32)},
|
||||
{"rxUpdateRate", -1, UNSIGNED, PREDICT(PREVIOUS), ENCODING(UNSIGNED_VB)},
|
||||
|
||||
{"hwHealthStatus", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
{"powerSupplyImpedance", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
|
@ -436,8 +467,6 @@ static const blackboxSimpleFieldDefinition_t blackboxSlowFields[] = {
|
|||
{"escRPM", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
{"escTemperature", -1, SIGNED, PREDICT(PREVIOUS), ENCODING(SIGNED_VB)},
|
||||
#endif
|
||||
{"rxUpdateRate", -1, UNSIGNED, PREDICT(PREVIOUS), ENCODING(UNSIGNED_VB)},
|
||||
{"activeWpNumber", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
};
|
||||
|
||||
typedef enum BlackboxState {
|
||||
|
@ -533,7 +562,9 @@ typedef struct blackboxGpsState_s {
|
|||
|
||||
// This data is updated really infrequently:
|
||||
typedef struct blackboxSlowState_s {
|
||||
uint32_t flightModeFlags; // extend this data size (from uint16_t)
|
||||
uint32_t rcModeFlags;
|
||||
uint32_t rcModeFlags2;
|
||||
uint32_t activeFlightModeFlags;
|
||||
uint32_t stateFlags;
|
||||
uint8_t failsafePhase;
|
||||
bool rxSignalReceived;
|
||||
|
@ -566,7 +597,7 @@ extern boxBitmask_t rcModeActivationMask;
|
|||
static BlackboxState blackboxState = BLACKBOX_STATE_DISABLED;
|
||||
|
||||
static uint32_t blackboxLastArmingBeep = 0;
|
||||
static uint32_t blackboxLastFlightModeFlags = 0;
|
||||
static uint32_t blackboxLastRcModeFlags = 0;
|
||||
|
||||
static struct {
|
||||
uint32_t headerIndex;
|
||||
|
@ -643,7 +674,45 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
|||
return (getMotorCount() >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1) && blackboxIncludeFlag(BLACKBOX_FEATURE_MOTORS);
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_SERVOS:
|
||||
return isMixerUsingServos();
|
||||
return blackboxIncludeFlag(BLACKBOX_FEATURE_SERVOS) && isMixerUsingServos();
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_2:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_3:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_4:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_5:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_6:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_7:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_8:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_9:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_10:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_11:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_12:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_13:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_14:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_15:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_16:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_17:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_18:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_19:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_20:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_21:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_22:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_23:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_24:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_25:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_26:
|
||||
/*
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_27:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_28:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_29:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_30:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_31:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_32:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_33:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_34:
|
||||
*/
|
||||
return ((FlightLogFieldCondition)getServoCount() >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1 + 1) && blackboxIncludeFlag(BLACKBOX_FEATURE_SERVOS);
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1:
|
||||
|
@ -944,7 +1013,8 @@ static void writeIntraframe(void)
|
|||
}
|
||||
|
||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_SERVOS)) {
|
||||
for (int x = 0; x < MAX_SUPPORTED_SERVOS; x++) {
|
||||
const int servoCount = getServoCount();
|
||||
for (int x = 0; x < servoCount; x++) {
|
||||
//Assume that servos spends most of its time around the center
|
||||
blackboxWriteSignedVB(blackboxCurrent->servo[x] - 1500);
|
||||
}
|
||||
|
@ -1203,7 +1273,7 @@ static void writeInterframe(void)
|
|||
}
|
||||
|
||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_SERVOS)) {
|
||||
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, servo), MAX_SUPPORTED_SERVOS);
|
||||
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, servo), getServoCount());
|
||||
}
|
||||
|
||||
blackboxWriteSignedVB(blackboxCurrent->navState - blackboxLast->navState);
|
||||
|
@ -1260,7 +1330,10 @@ static void writeSlowFrame(void)
|
|||
|
||||
blackboxWrite('S');
|
||||
|
||||
blackboxWriteUnsignedVB(slowHistory.flightModeFlags);
|
||||
blackboxWriteUnsignedVB(slowHistory.activeWpNumber);
|
||||
blackboxWriteUnsignedVB(slowHistory.rcModeFlags);
|
||||
blackboxWriteUnsignedVB(slowHistory.rcModeFlags2);
|
||||
blackboxWriteUnsignedVB(slowHistory.activeFlightModeFlags);
|
||||
blackboxWriteUnsignedVB(slowHistory.stateFlags);
|
||||
|
||||
/*
|
||||
|
@ -1271,6 +1344,8 @@ static void writeSlowFrame(void)
|
|||
values[2] = slowHistory.rxFlightChannelsValid ? 1 : 0;
|
||||
blackboxWriteTag2_3S32(values);
|
||||
|
||||
blackboxWriteUnsignedVB(slowHistory.rxUpdateRate);
|
||||
|
||||
blackboxWriteUnsignedVB(slowHistory.hwHealthStatus);
|
||||
|
||||
blackboxWriteUnsignedVB(slowHistory.powerSupplyImpedance);
|
||||
|
@ -1296,8 +1371,6 @@ static void writeSlowFrame(void)
|
|||
blackboxWriteUnsignedVB(slowHistory.escRPM);
|
||||
blackboxWriteSignedVB(slowHistory.escTemperature);
|
||||
#endif
|
||||
blackboxWriteUnsignedVB(slowHistory.rxUpdateRate);
|
||||
blackboxWriteUnsignedVB(slowHistory.activeWpNumber);
|
||||
|
||||
blackboxSlowFrameIterationTimer = 0;
|
||||
}
|
||||
|
@ -1307,27 +1380,21 @@ static void writeSlowFrame(void)
|
|||
*/
|
||||
static void loadSlowState(blackboxSlowState_t *slow)
|
||||
{
|
||||
memcpy(&slow->flightModeFlags, &rcModeActivationMask, sizeof(slow->flightModeFlags)); //was flightModeFlags;
|
||||
slow->activeWpNumber = getActiveWpNumber();
|
||||
|
||||
slow->rcModeFlags = rcModeActivationMask.bits[0]; // first 32 bits of boxId_e
|
||||
slow->rcModeFlags2 = rcModeActivationMask.bits[1]; // remaining bits of boxId_e
|
||||
|
||||
// Also log Nav auto enabled flight modes rather than just those selected by boxmode
|
||||
if (FLIGHT_MODE(ANGLE_MODE)) {
|
||||
slow->flightModeFlags |= (1 << BOXANGLE);
|
||||
}
|
||||
if (FLIGHT_MODE(NAV_ALTHOLD_MODE)) {
|
||||
slow->flightModeFlags |= (1 << BOXNAVALTHOLD);
|
||||
}
|
||||
if (FLIGHT_MODE(NAV_RTH_MODE)) {
|
||||
slow->flightModeFlags |= (1 << BOXNAVRTH);
|
||||
}
|
||||
if (navigationGetHeadingControlState() == NAV_HEADING_CONTROL_AUTO) {
|
||||
slow->flightModeFlags |= (1 << BOXHEADINGHOLD);
|
||||
}
|
||||
if (navigationRequiresTurnAssistance()) {
|
||||
slow->flightModeFlags |= (1 << BOXTURNASSIST);
|
||||
slow->rcModeFlags |= (1 << BOXHEADINGHOLD);
|
||||
}
|
||||
slow->activeFlightModeFlags = flightModeFlags;
|
||||
slow->stateFlags = stateFlags;
|
||||
slow->failsafePhase = failsafePhase();
|
||||
slow->rxSignalReceived = rxIsReceivingSignal();
|
||||
slow->rxFlightChannelsValid = rxAreFlightChannelsValid();
|
||||
slow->rxUpdateRate = getRcUpdateFrequency();
|
||||
slow->hwHealthStatus = (getHwGyroStatus() << 2 * 0) | // Pack hardware health status into a bit field.
|
||||
(getHwAccelerometerStatus() << 2 * 1) | // Use raw hardwareSensorStatus_e values and pack them using 2 bits per value
|
||||
(getHwCompassStatus() << 2 * 2) | // Report GYRO in 2 lowest bits, then ACC, COMPASS, BARO, GPS, RANGEFINDER and PITOT
|
||||
|
@ -1379,9 +1446,6 @@ static void loadSlowState(blackboxSlowState_t *slow)
|
|||
slow->escRPM = escSensor->rpm;
|
||||
slow->escTemperature = escSensor->temperature;
|
||||
#endif
|
||||
|
||||
slow->rxUpdateRate = getRcUpdateFrequency();
|
||||
slow->activeWpNumber = getActiveWpNumber();
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -1439,6 +1503,9 @@ static void blackboxValidateConfig(void)
|
|||
#endif
|
||||
#ifdef USE_SDCARD
|
||||
case BLACKBOX_DEVICE_SDCARD:
|
||||
#endif
|
||||
#if defined(SITL_BUILD)
|
||||
case BLACKBOX_DEVICE_FILE:
|
||||
#endif
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
// Device supported, leave the setting alone
|
||||
|
@ -1498,7 +1565,7 @@ void blackboxStart(void)
|
|||
* it finally plays the beep for this arming event.
|
||||
*/
|
||||
blackboxLastArmingBeep = getArmingBeepTimeMicros();
|
||||
memcpy(&blackboxLastFlightModeFlags, &rcModeActivationMask, sizeof(blackboxLastFlightModeFlags)); // record startup status
|
||||
memcpy(&blackboxLastRcModeFlags, &rcModeActivationMask, sizeof(blackboxLastRcModeFlags)); // record startup status
|
||||
|
||||
blackboxSetState(BLACKBOX_STATE_PREPARE_LOG_FILE);
|
||||
}
|
||||
|
@ -1674,7 +1741,8 @@ static void loadMainState(timeUs_t currentTimeUs)
|
|||
|
||||
blackboxCurrent->rssi = getRSSI();
|
||||
|
||||
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
const int servoCount = getServoCount();
|
||||
for (int i = 0; i < servoCount; i++) {
|
||||
blackboxCurrent->servo[i] = servo[i];
|
||||
}
|
||||
|
||||
|
@ -1850,9 +1918,9 @@ static bool blackboxWriteSysinfo(void)
|
|||
BLACKBOX_PRINT_HEADER_LINE("Craft name", "%s", systemConfig()->craftName);
|
||||
BLACKBOX_PRINT_HEADER_LINE("P interval", "%u/%u", blackboxConfig()->rate_num, blackboxConfig()->rate_denom);
|
||||
BLACKBOX_PRINT_HEADER_LINE("minthrottle", "%d", getThrottleIdleValue());
|
||||
BLACKBOX_PRINT_HEADER_LINE("maxthrottle", "%d", motorConfig()->maxthrottle);
|
||||
BLACKBOX_PRINT_HEADER_LINE("maxthrottle", "%d", getMaxThrottle());
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_scale", "0x%x", castFloatBytesToInt(1.0f));
|
||||
BLACKBOX_PRINT_HEADER_LINE("motorOutput", "%d,%d", getThrottleIdleValue(),motorConfig()->maxthrottle);
|
||||
BLACKBOX_PRINT_HEADER_LINE("motorOutput", "%d,%d", getThrottleIdleValue(),getMaxThrottle());
|
||||
BLACKBOX_PRINT_HEADER_LINE("acc_1G", "%u", acc.dev.acc_1G);
|
||||
|
||||
#ifdef USE_ADC
|
||||
|
@ -1921,9 +1989,8 @@ static bool blackboxWriteSysinfo(void)
|
|||
BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_type", "%d", pidProfile()->dterm_lpf_type);
|
||||
BLACKBOX_PRINT_HEADER_LINE("deadband", "%d", rcControlsConfig()->deadband);
|
||||
BLACKBOX_PRINT_HEADER_LINE("yaw_deadband", "%d", rcControlsConfig()->yaw_deadband);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf", "%d", gyroConfig()->gyro_lpf);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf", "%d", GYRO_LPF_256HZ);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf_hz", "%d", gyroConfig()->gyro_main_lpf_hz);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf_type", "%d", gyroConfig()->gyro_main_lpf_type);
|
||||
#ifdef USE_DYNAMIC_FILTERS
|
||||
BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchQ", "%d", gyroConfig()->dynamicGyroNotchQ);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchMinHz", "%d", gyroConfig()->dynamicGyroNotchMinHz);
|
||||
|
@ -1946,8 +2013,6 @@ static bool blackboxWriteSysinfo(void)
|
|||
BLACKBOX_PRINT_HEADER_LINE("waypoints", "%d,%d", getWaypointCount(),isWaypointListValid());
|
||||
BLACKBOX_PRINT_HEADER_LINE("acc_notch_hz", "%d", accelerometerConfig()->acc_notch_hz);
|
||||
BLACKBOX_PRINT_HEADER_LINE("acc_notch_cutoff", "%d", accelerometerConfig()->acc_notch_cutoff);
|
||||
BLACKBOX_PRINT_HEADER_LINE("pidSumLimit", "%d", pidProfile()->pidSumLimit);
|
||||
BLACKBOX_PRINT_HEADER_LINE("pidSumLimitYaw", "%d", pidProfile()->pidSumLimitYaw);
|
||||
BLACKBOX_PRINT_HEADER_LINE("axisAccelerationLimitYaw", "%d", pidProfile()->axisAccelerationLimitYaw);
|
||||
BLACKBOX_PRINT_HEADER_LINE("axisAccelerationLimitRollPitch", "%d", pidProfile()->axisAccelerationLimitRollPitch);
|
||||
#ifdef USE_RPM_FILTER
|
||||
|
@ -2026,10 +2091,10 @@ static void blackboxCheckAndLogArmingBeep(void)
|
|||
static void blackboxCheckAndLogFlightMode(void)
|
||||
{
|
||||
// Use != so that we can still detect a change if the counter wraps
|
||||
if (memcmp(&rcModeActivationMask, &blackboxLastFlightModeFlags, sizeof(blackboxLastFlightModeFlags))) {
|
||||
if (memcmp(&rcModeActivationMask, &blackboxLastRcModeFlags, sizeof(blackboxLastRcModeFlags))) {
|
||||
flightLogEvent_flightMode_t eventData; // Add new data for current flight mode flags
|
||||
eventData.lastFlags = blackboxLastFlightModeFlags;
|
||||
memcpy(&blackboxLastFlightModeFlags, &rcModeActivationMask, sizeof(blackboxLastFlightModeFlags));
|
||||
eventData.lastFlags = blackboxLastRcModeFlags;
|
||||
memcpy(&blackboxLastRcModeFlags, &rcModeActivationMask, sizeof(blackboxLastRcModeFlags));
|
||||
memcpy(&eventData.flags, &rcModeActivationMask, sizeof(eventData.flags));
|
||||
blackboxLogEvent(FLIGHT_LOG_EVENT_FLIGHTMODE, (flightLogEventData_t *)&eventData);
|
||||
}
|
||||
|
|
|
@ -35,6 +35,7 @@ typedef enum {
|
|||
BLACKBOX_FEATURE_GYRO_PEAKS_ROLL = 1 << 10,
|
||||
BLACKBOX_FEATURE_GYRO_PEAKS_PITCH = 1 << 11,
|
||||
BLACKBOX_FEATURE_GYRO_PEAKS_YAW = 1 << 12,
|
||||
BLACKBOX_FEATURE_SERVOS = 1 << 13,
|
||||
} blackboxFeatureMask_e;
|
||||
typedef struct blackboxConfig_s {
|
||||
uint16_t rate_num;
|
||||
|
@ -55,4 +56,4 @@ void blackboxFinish(void);
|
|||
bool blackboxMayEditConfig(void);
|
||||
void blackboxIncludeFlagSet(uint32_t mask);
|
||||
void blackboxIncludeFlagClear(uint32_t mask);
|
||||
bool blackboxIncludeFlag(uint32_t mask);
|
||||
bool blackboxIncludeFlag(uint32_t mask);
|
||||
|
|
|
@ -33,7 +33,44 @@ typedef enum FlightLogFieldCondition {
|
|||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_6,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8,
|
||||
|
||||
FLIGHT_LOG_FIELD_CONDITION_SERVOS,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_2,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_3,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_4,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_5,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_6,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_7,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_8,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_9,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_10,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_11,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_12,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_13,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_14,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_15,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_16,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_17,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_18,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_19,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_20,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_21,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_22,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_23,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_24,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_25,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_26,
|
||||
/*
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_27,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_28,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_29,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_30,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_31,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_32,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_33,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_34,
|
||||
*/
|
||||
|
||||
FLIGHT_LOG_FIELD_CONDITION_MAG,
|
||||
FLIGHT_LOG_FIELD_CONDITION_BARO,
|
||||
|
|
|
@ -19,6 +19,11 @@
|
|||
#include <stdarg.h>
|
||||
#include <string.h>
|
||||
|
||||
#if defined(SITL_BUILD)
|
||||
#include <stdio.h>
|
||||
#include <time.h>
|
||||
#endif
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_BLACKBOX
|
||||
|
@ -35,6 +40,10 @@
|
|||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#ifdef USE_SDCARD
|
||||
#include "drivers/sdcard/sdcard.h"
|
||||
#endif
|
||||
|
||||
#include "io/asyncfatfs/asyncfatfs.h"
|
||||
#include "io/flashfs.h"
|
||||
#include "io/serial.h"
|
||||
|
@ -77,6 +86,12 @@ static struct {
|
|||
|
||||
#endif
|
||||
|
||||
#if defined(SITL_BUILD)
|
||||
static struct {
|
||||
FILE *file_handler;
|
||||
} blackboxFile;
|
||||
#endif
|
||||
|
||||
#ifndef UNIT_TEST
|
||||
void blackboxOpen(void)
|
||||
{
|
||||
|
@ -99,6 +114,11 @@ void blackboxWrite(uint8_t value)
|
|||
case BLACKBOX_DEVICE_SDCARD:
|
||||
afatfs_fputc(blackboxSDCard.logFile, value);
|
||||
break;
|
||||
#endif
|
||||
#if defined(SITL_BUILD)
|
||||
case BLACKBOX_DEVICE_FILE:
|
||||
fputc(value, blackboxFile.file_handler);
|
||||
break;
|
||||
#endif
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
default:
|
||||
|
@ -129,6 +149,13 @@ int blackboxPrint(const char *s)
|
|||
break;
|
||||
#endif
|
||||
|
||||
#if defined(SITL_BUILD)
|
||||
case BLACKBOX_DEVICE_FILE:
|
||||
length = strlen(s);
|
||||
fputs(s, blackboxFile.file_handler);
|
||||
break;
|
||||
#endif
|
||||
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
default:
|
||||
pos = (uint8_t*) s;
|
||||
|
@ -192,6 +219,12 @@ bool blackboxDeviceFlushForce(void)
|
|||
return afatfs_flush();
|
||||
#endif
|
||||
|
||||
#if defined(SITL_BUILD)
|
||||
case BLACKBOX_DEVICE_FILE:
|
||||
fflush(blackboxFile.file_handler);
|
||||
return true;
|
||||
#endif
|
||||
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
|
@ -267,6 +300,26 @@ bool blackboxDeviceOpen(void)
|
|||
return true;
|
||||
break;
|
||||
#endif
|
||||
#if defined(SITL_BUILD)
|
||||
case BLACKBOX_DEVICE_FILE:
|
||||
{
|
||||
const time_t now = time(NULL);
|
||||
const struct tm *t = localtime(&now);
|
||||
char filename[32];
|
||||
strftime(filename, sizeof(filename), "%Y_%m_%d_%H%M%S.TXT", t);
|
||||
|
||||
blackboxFile.file_handler = fopen(filename, "wb");
|
||||
if (blackboxFile.file_handler == NULL) {
|
||||
fprintf(stderr, "[BlackBox] Failed to create log file\n");
|
||||
return false;
|
||||
}
|
||||
fprintf(stderr, "[BlackBox] Created %s\n", filename);
|
||||
}
|
||||
|
||||
blackboxMaxHeaderBytesPerIteration = BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION;
|
||||
return true;
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
|
@ -298,6 +351,12 @@ void blackboxDeviceClose(void)
|
|||
// Some flash device, e.g., NAND devices, require explicit close to flush internally buffered data.
|
||||
flashfsClose();
|
||||
break;
|
||||
#endif
|
||||
#if defined(SITL_BUILD)
|
||||
case BLACKBOX_DEVICE_FILE:
|
||||
fclose(blackboxFile.file_handler);
|
||||
blackboxFile.file_handler = NULL;
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
;
|
||||
|
@ -502,11 +561,50 @@ bool isBlackboxDeviceFull(void)
|
|||
return afatfs_isFull();
|
||||
#endif
|
||||
|
||||
#if defined (SITL_BUILD)
|
||||
case BLACKBOX_DEVICE_FILE:
|
||||
return false;
|
||||
#endif
|
||||
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
bool isBlackboxDeviceWorking(void)
|
||||
{
|
||||
switch (blackboxConfig()->device) {
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
return blackboxPort != NULL;
|
||||
#ifdef USE_SDCARD
|
||||
case BLACKBOX_DEVICE_SDCARD:
|
||||
return sdcard_isInserted() && sdcard_isFunctional() && (afatfs_getFilesystemState() == AFATFS_FILESYSTEM_STATE_READY);
|
||||
#endif
|
||||
#ifdef USE_FLASHFS
|
||||
case BLACKBOX_DEVICE_FLASH:
|
||||
return flashfsIsReady();
|
||||
#endif
|
||||
#if defined(SITL_BUILD)
|
||||
case BLACKBOX_DEVICE_FILE:
|
||||
return blackboxFile.file_handler != NULL;
|
||||
#endif
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
int32_t blackboxGetLogNumber(void)
|
||||
{
|
||||
switch (blackboxConfig()->device) {
|
||||
#ifdef USE_SDCARD
|
||||
case BLACKBOX_DEVICE_SDCARD:
|
||||
return blackboxSDCard.largestLogFileNumber;
|
||||
#endif
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Call once every loop iteration in order to maintain the global blackboxHeaderBudget with the number of bytes we can
|
||||
* transmit this iteration.
|
||||
|
@ -528,6 +626,11 @@ void blackboxReplenishHeaderBudget(void)
|
|||
case BLACKBOX_DEVICE_SDCARD:
|
||||
freeSpace = afatfs_getFreeBufferSpace();
|
||||
break;
|
||||
#endif
|
||||
#if defined(SITL_BUILD)
|
||||
case BLACKBOX_DEVICE_FILE:
|
||||
freeSpace = BLACKBOX_MAX_ACCUMULATED_HEADER_BUDGET;
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
freeSpace = 0;
|
||||
|
@ -597,6 +700,12 @@ blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes)
|
|||
return BLACKBOX_RESERVE_TEMPORARY_FAILURE;
|
||||
#endif
|
||||
|
||||
#if defined(SITL_BUILD)
|
||||
case BLACKBOX_DEVICE_FILE:
|
||||
// Assume that all writes will fit in the file's buffers
|
||||
return BLACKBOX_RESERVE_TEMPORARY_FAILURE;
|
||||
#endif
|
||||
|
||||
default:
|
||||
return BLACKBOX_RESERVE_PERMANENT_FAILURE;
|
||||
}
|
||||
|
|
|
@ -31,6 +31,9 @@ typedef enum BlackboxDevice {
|
|||
#ifdef USE_SDCARD
|
||||
BLACKBOX_DEVICE_SDCARD = 2,
|
||||
#endif
|
||||
#if defined(SITL_BUILD)
|
||||
BLACKBOX_DEVICE_FILE = 3,
|
||||
#endif
|
||||
|
||||
BLACKBOX_DEVICE_END
|
||||
} BlackboxDevice;
|
||||
|
@ -67,6 +70,8 @@ bool blackboxDeviceBeginLog(void);
|
|||
bool blackboxDeviceEndLog(bool retainLog);
|
||||
|
||||
bool isBlackboxDeviceFull(void);
|
||||
bool isBlackboxDeviceWorking(void);
|
||||
int32_t blackboxGetLogNumber(void);
|
||||
|
||||
void blackboxReplenishHeaderBudget(void);
|
||||
blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes);
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
#endif
|
||||
|
||||
#ifdef __APPLE__
|
||||
#define FASTRAM __attribute__ ((section("__DATA,__.fastram_bss"), aligned(4)))
|
||||
#define FASTRAM __attribute__ ((section("__DATA,__.fastram_bss"), aligned(8)))
|
||||
#else
|
||||
#define FASTRAM __attribute__ ((section(".fastram_bss"), aligned(4)))
|
||||
#endif
|
||||
|
|
|
@ -21,6 +21,8 @@
|
|||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#define DEBUG32_VALUE_COUNT 8
|
||||
extern int32_t debug[DEBUG32_VALUE_COUNT];
|
||||
extern uint8_t debugMode;
|
||||
|
@ -72,5 +74,16 @@ typedef enum {
|
|||
DEBUG_RATE_DYNAMICS,
|
||||
DEBUG_LANDING,
|
||||
DEBUG_POS_EST,
|
||||
DEBUG_COUNT
|
||||
DEBUG_ADAPTIVE_FILTER,
|
||||
DEBUG_HEADTRACKING,
|
||||
DEBUG_GPS,
|
||||
DEBUG_LULU,
|
||||
DEBUG_SBUS2,
|
||||
DEBUG_COUNT // also update debugModeNames in cli.c
|
||||
} debugType_e;
|
||||
|
||||
#ifdef SITL_BUILD
|
||||
#define SD(X) (X)
|
||||
#else
|
||||
#define SD(X)
|
||||
#endif
|
||||
|
|
|
@ -18,8 +18,12 @@
|
|||
#define STR_HELPER(x) #x
|
||||
#define STR(x) STR_HELPER(x)
|
||||
#define FC_VERSION_STRING STR(FC_VERSION_MAJOR) "." STR(FC_VERSION_MINOR) "." STR(FC_VERSION_PATCH_LEVEL)
|
||||
#ifndef FC_VERSION_TYPE
|
||||
#define FC_VERSION_TYPE ""
|
||||
#endif
|
||||
#define FC_FIRMWARE_NAME "INAV"
|
||||
|
||||
|
||||
#define MW_VERSION 231
|
||||
|
||||
extern const char* const compilerVersion;
|
||||
|
|
|
@ -137,6 +137,30 @@ static long cmsx_PidWriteback(const OSD_Entry *self)
|
|||
return 0;
|
||||
}
|
||||
|
||||
static const OSD_Entry cmsx_menuEzTuneEntries[] =
|
||||
{
|
||||
OSD_LABEL_DATA_ENTRY("-- EZTUNE --", profileIndexString),
|
||||
|
||||
OSD_SETTING_ENTRY("ENABLED", SETTING_EZ_ENABLED),
|
||||
OSD_SETTING_ENTRY("FILTER HZ", SETTING_EZ_FILTER_HZ),
|
||||
OSD_SETTING_ENTRY("RATIO", SETTING_EZ_AXIS_RATIO),
|
||||
OSD_SETTING_ENTRY("RESP.", SETTING_EZ_RESPONSE),
|
||||
OSD_SETTING_ENTRY("DAMP.", SETTING_EZ_DAMPING),
|
||||
OSD_SETTING_ENTRY("STAB.", SETTING_EZ_STABILITY),
|
||||
OSD_SETTING_ENTRY("AGGR.", SETTING_EZ_AGGRESSIVENESS),
|
||||
OSD_SETTING_ENTRY("RATE", SETTING_EZ_RATE),
|
||||
OSD_SETTING_ENTRY("EXPO", SETTING_EZ_EXPO),
|
||||
|
||||
OSD_BACK_AND_END_ENTRY,
|
||||
};
|
||||
|
||||
static const CMS_Menu cmsx_menuEzTune = {
|
||||
.onEnter = NULL,
|
||||
.onExit = NULL,
|
||||
.onGlobalExit = NULL,
|
||||
.entries = cmsx_menuEzTuneEntries
|
||||
};
|
||||
|
||||
static const OSD_Entry cmsx_menuPidEntries[] =
|
||||
{
|
||||
OSD_LABEL_DATA_ENTRY("-- PID --", profileIndexString),
|
||||
|
@ -198,6 +222,8 @@ static const OSD_Entry cmsx_menuPidAltMagEntries[] =
|
|||
{
|
||||
OSD_LABEL_DATA_ENTRY("-- ALT&MAG --", profileIndexString),
|
||||
|
||||
OSD_SETTING_ENTRY("FW ALT RESPONSE", SETTING_NAV_FW_ALT_CONTROL_RESPONSE),
|
||||
|
||||
OTHER_PIDFF_ENTRY("ALT P", &cmsx_pidPosZ.P),
|
||||
OTHER_PIDFF_ENTRY("ALT I", &cmsx_pidPosZ.I),
|
||||
OTHER_PIDFF_ENTRY("ALT D", &cmsx_pidPosZ.D),
|
||||
|
@ -398,7 +424,6 @@ static const CMS_Menu cmsx_menuProfileOther = {
|
|||
static const OSD_Entry cmsx_menuFilterPerProfileEntries[] =
|
||||
{
|
||||
OSD_LABEL_DATA_ENTRY("-- FILTERING --", profileIndexString),
|
||||
OSD_SETTING_ENTRY("HARDWARE LPF", SETTING_GYRO_HARDWARE_LPF),
|
||||
OSD_SETTING_ENTRY("GYRO MAIN", SETTING_GYRO_MAIN_LPF_HZ),
|
||||
OSD_SETTING_ENTRY("DTERM LPF", SETTING_DTERM_LPF_HZ),
|
||||
#ifdef USE_DYNAMIC_FILTERS
|
||||
|
@ -458,6 +483,7 @@ static const OSD_Entry cmsx_menuImuEntries[] =
|
|||
|
||||
// Profile dependent
|
||||
OSD_UINT8_CALLBACK_ENTRY("PID PROF", cmsx_profileIndexOnChange, (&(const OSD_UINT8_t){ &tmpProfileIndex, 1, MAX_PROFILE_COUNT, 1})),
|
||||
OSD_SUBMENU_ENTRY("EZTUNE", &cmsx_menuEzTune),
|
||||
OSD_SUBMENU_ENTRY("PID", &cmsx_menuPid),
|
||||
OSD_SUBMENU_ENTRY("PID ALTMAG", &cmsx_menuPidAltMag),
|
||||
OSD_SUBMENU_ENTRY("PID GPSNAV", &cmsx_menuPidGpsnav),
|
||||
|
|
|
@ -45,8 +45,9 @@ static const OSD_Entry cmsx_menuNavSettingsEntries[] =
|
|||
OSD_SETTING_ENTRY("MC NAV SPEED", SETTING_NAV_AUTO_SPEED),
|
||||
OSD_SETTING_ENTRY("MC MAX NAV SPEED", SETTING_NAV_MAX_AUTO_SPEED),
|
||||
OSD_SETTING_ENTRY("MAX CRUISE SPEED", SETTING_NAV_MANUAL_SPEED),
|
||||
OSD_SETTING_ENTRY("MAX NAV CLIMB RATE", SETTING_NAV_AUTO_CLIMB_RATE),
|
||||
OSD_SETTING_ENTRY("MAX AH CLIMB RATE", SETTING_NAV_MANUAL_CLIMB_RATE),
|
||||
OSD_SETTING_ENTRY("MAX NAV CLIMB RATE", SETTING_NAV_MC_AUTO_CLIMB_RATE),
|
||||
OSD_SETTING_ENTRY("MAX MC AH CLIMB RATE", SETTING_NAV_MC_MANUAL_CLIMB_RATE),
|
||||
OSD_SETTING_ENTRY("MAX FW AH CLIMB RATE", SETTING_NAV_FW_MANUAL_CLIMB_RATE),
|
||||
OSD_SETTING_ENTRY("MC MAX BANK ANGLE", SETTING_NAV_MC_BANK_ANGLE),
|
||||
OSD_SETTING_ENTRY("MC ALTHOLD THROT", SETTING_NAV_MC_ALTHOLD_THROTTLE),
|
||||
OSD_SETTING_ENTRY("MC HOVER THR", SETTING_NAV_MC_HOVER_THR),
|
||||
|
|
|
@ -147,10 +147,10 @@ static const OSD_Entry menuCrsfRxEntries[]=
|
|||
OSD_SETTING_ENTRY("LQ ALARM LEVEL", SETTING_OSD_LINK_QUALITY_ALARM),
|
||||
OSD_SETTING_ENTRY("SNR ALARM LEVEL", SETTING_OSD_SNR_ALARM),
|
||||
OSD_SETTING_ENTRY("RX SENSITIVITY", SETTING_OSD_RSSI_DBM_MIN),
|
||||
OSD_ELEMENT_ENTRY("RX RSSI DBM", OSD_CRSF_RSSI_DBM),
|
||||
OSD_ELEMENT_ENTRY("RX LQ", OSD_CRSF_LQ),
|
||||
OSD_ELEMENT_ENTRY("RX SNR ALARM", OSD_CRSF_SNR_DB),
|
||||
OSD_ELEMENT_ENTRY("TX POWER", OSD_CRSF_TX_POWER),
|
||||
OSD_ELEMENT_ENTRY("RX RSSI DBM", OSD_RSSI_DBM),
|
||||
OSD_ELEMENT_ENTRY("RX LQ", OSD_LQ_UPLINK),
|
||||
OSD_ELEMENT_ENTRY("RX SNR ALARM", OSD_SNR_DB),
|
||||
OSD_ELEMENT_ENTRY("TX POWER", OSD_TX_POWER_UPLINK),
|
||||
|
||||
OSD_BACK_AND_END_ENTRY,
|
||||
};
|
||||
|
@ -237,6 +237,7 @@ static const OSD_Entry menuOsdElemsEntries[] =
|
|||
OSD_ELEMENT_ENTRY("RADAR", OSD_RADAR),
|
||||
OSD_ELEMENT_ENTRY("MAP SCALE", OSD_MAP_SCALE),
|
||||
OSD_ELEMENT_ENTRY("MAP REFERENCE", OSD_MAP_REFERENCE),
|
||||
OSD_ELEMENT_ENTRY("FORMATION FLIGHT", OSD_FORMATION_FLIGHT),
|
||||
#endif
|
||||
OSD_ELEMENT_ENTRY("EXPO", OSD_RC_EXPO),
|
||||
OSD_ELEMENT_ENTRY("YAW EXPO", OSD_RC_YAW_EXPO),
|
||||
|
|
|
@ -26,6 +26,12 @@
|
|||
|
||||
//type of elements
|
||||
|
||||
#ifndef __APPLE__
|
||||
#define OSD_ENTRY_ATTR __attribute__((packed))
|
||||
#else
|
||||
#define OSD_ENTRY_ATTR
|
||||
#endif
|
||||
|
||||
typedef enum
|
||||
{
|
||||
OME_Label,
|
||||
|
@ -71,7 +77,7 @@ typedef struct
|
|||
const void * const data;
|
||||
const uint8_t type; // from OSD_MenuElement
|
||||
uint8_t flags;
|
||||
} __attribute__((packed)) OSD_Entry;
|
||||
} OSD_ENTRY_ATTR OSD_Entry;
|
||||
|
||||
// Bits in flags
|
||||
#define PRINT_VALUE (1 << 0) // Value has been changed, need to redraw
|
||||
|
|
|
@ -23,10 +23,10 @@
|
|||
#include "platform.h"
|
||||
|
||||
#include "common/filter.h"
|
||||
#include "common/lulu.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
#include "common/time.h"
|
||||
|
||||
// NULL filter
|
||||
float nullFilterApply(void *filter, float input)
|
||||
{
|
||||
|
@ -326,6 +326,8 @@ void initFilter(const uint8_t filterType, filter_t *filter, const float cutoffFr
|
|||
pt2FilterInit(&filter->pt2, pt2FilterGain(cutoffFrequency, dT));
|
||||
} if (filterType == FILTER_PT3) {
|
||||
pt3FilterInit(&filter->pt3, pt3FilterGain(cutoffFrequency, dT));
|
||||
} if (filterType == FILTER_LULU) {
|
||||
luluFilterInit(&filter->lulu, cutoffFrequency);
|
||||
} else {
|
||||
biquadFilterInitLPF(&filter->biquad, cutoffFrequency, refreshRate);
|
||||
}
|
||||
|
@ -341,8 +343,10 @@ void assignFilterApplyFn(uint8_t filterType, float cutoffFrequency, filterApplyF
|
|||
*applyFn = (filterApplyFnPtr) pt2FilterApply;
|
||||
} if (filterType == FILTER_PT3) {
|
||||
*applyFn = (filterApplyFnPtr) pt3FilterApply;
|
||||
} if (filterType == FILTER_LULU) {
|
||||
*applyFn = (filterApplyFnPtr) luluFilterApply;
|
||||
} else {
|
||||
*applyFn = (filterApplyFnPtr) biquadFilterApply;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -17,6 +17,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "lulu.h"
|
||||
|
||||
typedef struct rateLimitFilter_s {
|
||||
float state;
|
||||
} rateLimitFilter_t;
|
||||
|
@ -50,13 +52,15 @@ typedef union {
|
|||
pt1Filter_t pt1;
|
||||
pt2Filter_t pt2;
|
||||
pt3Filter_t pt3;
|
||||
luluFilter_t lulu;
|
||||
} filter_t;
|
||||
|
||||
typedef enum {
|
||||
FILTER_PT1 = 0,
|
||||
FILTER_BIQUAD,
|
||||
FILTER_PT2,
|
||||
FILTER_PT3
|
||||
FILTER_PT3,
|
||||
FILTER_LULU
|
||||
} filterType_e;
|
||||
|
||||
typedef enum {
|
||||
|
@ -134,4 +138,4 @@ void alphaBetaGammaFilterInit(alphaBetaGammaFilter_t *filter, float alpha, float
|
|||
float alphaBetaGammaFilterApply(alphaBetaGammaFilter_t *filter, float input);
|
||||
|
||||
void initFilter(uint8_t filterType, filter_t *filter, float cutoffFrequency, uint32_t refreshRate);
|
||||
void assignFilterApplyFn(uint8_t filterType, float cutoffFrequency, filterApplyFnPtr *applyFn);
|
||||
void assignFilterApplyFn(uint8_t filterType, float cutoffFrequency, filterApplyFnPtr *applyFn);
|
||||
|
|
|
@ -20,11 +20,12 @@
|
|||
#include <stdarg.h>
|
||||
#include <ctype.h>
|
||||
|
||||
#if defined(SEMIHOSTING)
|
||||
#if defined(SEMIHOSTING) || defined(SITL_BUILD)
|
||||
#include <stdio.h>
|
||||
#endif
|
||||
|
||||
#include "build/version.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/time.h"
|
||||
|
@ -125,6 +126,7 @@ static void logPrint(const char *buf, size_t size)
|
|||
fputc(buf[ii], stdout);
|
||||
}
|
||||
#endif
|
||||
SD(printf("%s\n", buf));
|
||||
if (logPort) {
|
||||
// Send data via UART (if configured & connected - a safeguard against zombie VCP)
|
||||
if (serialIsConnected(logPort)) {
|
||||
|
|
179
src/main/common/lulu.c
Normal file
179
src/main/common/lulu.c
Normal file
|
@ -0,0 +1,179 @@
|
|||
#include "lulu.h"
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "common/filter.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#ifdef __ARM_ACLE
|
||||
#include <arm_acle.h>
|
||||
#endif /* __ARM_ACLE */
|
||||
#include <fenv.h>
|
||||
|
||||
void luluFilterInit(luluFilter_t *filter, int N)
|
||||
{
|
||||
filter->N = constrain(N, 1, 15);
|
||||
filter->windowSize = filter->N * 2 + 1;
|
||||
filter->windowBufIndex = 0;
|
||||
|
||||
memset(filter->luluInterim, 0, sizeof(float) * (filter->windowSize));
|
||||
memset(filter->luluInterimB, 0, sizeof(float) * (filter->windowSize));
|
||||
}
|
||||
|
||||
FAST_CODE float fixRoad(float *series, float *seriesB, int index, int filterN, int windowSize)
|
||||
{
|
||||
float curVal = 0;
|
||||
float curValB = 0;
|
||||
for (int N = 1; N <= filterN; N++)
|
||||
{
|
||||
int indexNeg = (index + windowSize - 2 * N) % windowSize;
|
||||
int curIndex = (indexNeg + 1) % windowSize;
|
||||
float prevVal = series[indexNeg];
|
||||
float prevValB = seriesB[indexNeg];
|
||||
int indexPos = (curIndex + N) % windowSize;
|
||||
|
||||
for (int i = windowSize - 2 * N; i < windowSize - N; i++)
|
||||
{
|
||||
if (indexPos >= windowSize)
|
||||
{
|
||||
indexPos = 0;
|
||||
}
|
||||
if (curIndex >= windowSize)
|
||||
{
|
||||
curIndex = 0;
|
||||
}
|
||||
// curIndex = (2 - 1) % 3 = 1
|
||||
curVal = series[curIndex];
|
||||
curValB = seriesB[curIndex];
|
||||
float nextVal = series[indexPos];
|
||||
float nextValB = seriesB[indexPos];
|
||||
// onbump (s, 1, 1, 3)
|
||||
// if(onBump(series, curIndex, N, windowSize))
|
||||
if (prevVal < curVal && curVal > nextVal)
|
||||
{
|
||||
float maxValue = MAX(prevVal, nextVal);
|
||||
|
||||
series[curIndex] = maxValue;
|
||||
int k = curIndex;
|
||||
for (int j = 1; j < N; j++)
|
||||
{
|
||||
if (++k >= windowSize)
|
||||
{
|
||||
k = 0;
|
||||
}
|
||||
series[k] = maxValue;
|
||||
}
|
||||
}
|
||||
|
||||
if (prevValB < curValB && curValB > nextValB)
|
||||
{
|
||||
float maxValue = MAX(prevValB, nextValB);
|
||||
|
||||
curVal = maxValue;
|
||||
seriesB[curIndex] = maxValue;
|
||||
int k = curIndex;
|
||||
for (int j = 1; j < N; j++)
|
||||
{
|
||||
if (++k >= windowSize)
|
||||
{
|
||||
k = 0;
|
||||
}
|
||||
seriesB[k] = maxValue;
|
||||
}
|
||||
}
|
||||
prevVal = curVal;
|
||||
prevValB = curValB;
|
||||
curIndex++;
|
||||
indexPos++;
|
||||
}
|
||||
|
||||
curIndex = (indexNeg + 1) % windowSize;
|
||||
prevVal = series[indexNeg];
|
||||
prevValB = seriesB[indexNeg];
|
||||
indexPos = (curIndex + N) % windowSize;
|
||||
for (int i = windowSize - 2 * N; i < windowSize - N; i++)
|
||||
{
|
||||
if (indexPos >= windowSize)
|
||||
{
|
||||
indexPos = 0;
|
||||
}
|
||||
if (curIndex >= windowSize)
|
||||
{
|
||||
curIndex = 0;
|
||||
}
|
||||
// curIndex = (2 - 1) % 3 = 1
|
||||
curVal = series[curIndex];
|
||||
curValB = seriesB[curIndex];
|
||||
float nextVal = series[indexPos];
|
||||
float nextValB = seriesB[indexPos];
|
||||
|
||||
if (prevVal > curVal && curVal < nextVal)
|
||||
{
|
||||
float minValue = MIN(prevVal, nextVal);
|
||||
|
||||
curVal = minValue;
|
||||
series[curIndex] = minValue;
|
||||
int k = curIndex;
|
||||
for (int j = 1; j < N; j++)
|
||||
{
|
||||
if (++k >= windowSize)
|
||||
{
|
||||
k = 0;
|
||||
}
|
||||
series[k] = minValue;
|
||||
}
|
||||
}
|
||||
|
||||
if (prevValB > curValB && curValB < nextValB)
|
||||
{
|
||||
float minValue = MIN(prevValB, nextValB);
|
||||
curValB = minValue;
|
||||
seriesB[curIndex] = minValue;
|
||||
int k = curIndex;
|
||||
for (int j = 1; j < N; j++)
|
||||
{
|
||||
if (++k >= windowSize)
|
||||
{
|
||||
k = 0;
|
||||
}
|
||||
seriesB[k] = minValue;
|
||||
}
|
||||
}
|
||||
prevVal = curVal;
|
||||
prevValB = curValB;
|
||||
curIndex++;
|
||||
indexPos++;
|
||||
}
|
||||
}
|
||||
return (curVal - curValB) / 2;
|
||||
}
|
||||
|
||||
FAST_CODE float luluFilterPartialApply(luluFilter_t *filter, float input)
|
||||
{
|
||||
// This is the value N of the LULU filter.
|
||||
int filterN = filter->N;
|
||||
// This is the total window size for the rolling buffer
|
||||
int filterWindow = filter->windowSize;
|
||||
|
||||
int windowIndex = filter->windowBufIndex;
|
||||
float inputVal = input;
|
||||
int newIndex = (windowIndex + 1) % filterWindow;
|
||||
filter->windowBufIndex = newIndex;
|
||||
filter->luluInterim[windowIndex] = inputVal;
|
||||
filter->luluInterimB[windowIndex] = -inputVal;
|
||||
return fixRoad(filter->luluInterim, filter->luluInterimB, windowIndex, filterN, filterWindow);
|
||||
}
|
||||
|
||||
FAST_CODE float luluFilterApply(luluFilter_t *filter, float input)
|
||||
{
|
||||
// This is the UL filter
|
||||
float resultA = luluFilterPartialApply(filter, input);
|
||||
// We use the median interpretation of this filter to remove bias in the output
|
||||
return resultA;
|
||||
}
|
14
src/main/common/lulu.h
Normal file
14
src/main/common/lulu.h
Normal file
|
@ -0,0 +1,14 @@
|
|||
#pragma once
|
||||
|
||||
// Max N = 15
|
||||
typedef struct
|
||||
{
|
||||
int windowSize;
|
||||
int windowBufIndex;
|
||||
int N;
|
||||
float luluInterim[32] __attribute__((aligned(128)));
|
||||
float luluInterimB[32];
|
||||
} luluFilter_t;
|
||||
|
||||
void luluFilterInit(luluFilter_t *filter, int N);
|
||||
float luluFilterApply(luluFilter_t *filter, float input);
|
|
@ -123,6 +123,15 @@ int32_t wrap_18000(int32_t angle)
|
|||
return angle;
|
||||
}
|
||||
|
||||
int16_t wrap_180(int16_t angle)
|
||||
{
|
||||
if (angle > 180)
|
||||
angle -= 360;
|
||||
if (angle < -180)
|
||||
angle += 360;
|
||||
return angle;
|
||||
}
|
||||
|
||||
int32_t wrap_36000(int32_t angle)
|
||||
{
|
||||
if (angle >= 36000)
|
||||
|
@ -516,9 +525,25 @@ bool sensorCalibrationSolveForScale(sensorCalibrationState_t * state, float resu
|
|||
return sensorCalibrationValidateResult(result);
|
||||
}
|
||||
|
||||
float gaussian(const float x, const float mu, const float sigma) {
|
||||
return exp(-pow((double)(x - mu), 2) / (2 * pow((double)sigma, 2)));
|
||||
}
|
||||
|
||||
float bellCurve(const float x, const float curveWidth)
|
||||
{
|
||||
return powf(M_Ef, -sq(x) / (2.0f * sq(curveWidth)));
|
||||
return gaussian(x, 0.0f, curveWidth);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Calculate the attenuation of a value using a Gaussian function.
|
||||
* Retuns 1 for input 0 and ~0 for input width.
|
||||
* @param input The input value.
|
||||
* @param width The width of the Gaussian function.
|
||||
* @return The attenuation of the input value.
|
||||
*/
|
||||
float attenuation(const float input, const float width) {
|
||||
const float sigma = width / 2.35482f; // Approximately width / sqrt(2 * ln(2))
|
||||
return gaussian(input, 0.0f, sigma);
|
||||
}
|
||||
|
||||
float fast_fsqrtf(const float value) {
|
||||
|
|
|
@ -36,7 +36,7 @@
|
|||
#define RAD (M_PIf / 180.0f)
|
||||
|
||||
#define DEGREES_TO_CENTIDEGREES(angle) ((angle) * 100)
|
||||
#define CENTIDEGREES_TO_DEGREES(angle) ((angle) / 100.0f)
|
||||
#define CENTIDEGREES_TO_DEGREES(angle) ((angle) * 0.01f)
|
||||
|
||||
#define CENTIDEGREES_TO_DECIDEGREES(angle) ((angle) / 10.0f)
|
||||
#define DECIDEGREES_TO_CENTIDEGREES(angle) ((angle) * 10)
|
||||
|
@ -54,21 +54,29 @@
|
|||
#define RADIANS_TO_DECIDEGREES(angle) (((angle) * 10.0f) / RAD)
|
||||
|
||||
#define RADIANS_TO_CENTIDEGREES(angle) (((angle) * 100.0f) / RAD)
|
||||
#define CENTIDEGREES_TO_RADIANS(angle) (((angle) / 100.0f) * RAD)
|
||||
#define CENTIDEGREES_TO_RADIANS(angle) (((angle) * 0.01f) * RAD)
|
||||
|
||||
#define MILLIMETERS_TO_CENTIMETERS(mm) (mm / 10.0f)
|
||||
|
||||
#define CENTIMETERS_TO_CENTIFEET(cm) (cm / 0.3048f)
|
||||
#define CENTIMETERS_TO_FEET(cm) (cm / 30.48f)
|
||||
#define CENTIMETERS_TO_METERS(cm) (cm / 100.0f)
|
||||
#define CENTIMETERS_TO_METERS(cm) (cm * 0.01f)
|
||||
|
||||
#define METERS_TO_CENTIMETERS(m) (m * 100)
|
||||
#define METERS_TO_KILOMETERS(m) (m / 1000.0f)
|
||||
#define METERS_TO_MILES(m) (m / 1609.344f)
|
||||
#define METERS_TO_NAUTICALMILES(m) (m / 1852.00f)
|
||||
|
||||
#define MWH_TO_WH(mWh) (mWh / 1000.0f)
|
||||
|
||||
#define CMSEC_TO_CENTIMPH(cms) (cms * 2.2369363f)
|
||||
#define CMSEC_TO_CENTIKPH(cms) (cms * 3.6f)
|
||||
#define CMSEC_TO_CENTIKNOTS(cms) (cms * 1.943845f)
|
||||
|
||||
#define CMSEC_TO_MPH(cms) (CMSEC_TO_CENTIMPH(cms) / 100.0f)
|
||||
#define CMSEC_TO_KPH(cms) (CMSEC_TO_CENTIKPH(cms) / 100.0f)
|
||||
#define CMSEC_TO_KNOTS(cms) (CMSEC_TO_CENTIKNOTS(cms) / 100.0f)
|
||||
|
||||
#define C_TO_KELVIN(temp) (temp + 273.15f)
|
||||
|
||||
// Standard Sea Level values
|
||||
|
@ -162,6 +170,7 @@ int scaleRange(int x, int srcMin, int srcMax, int destMin, int destMax);
|
|||
float scaleRangef(float x, float srcMin, float srcMax, float destMin, float destMax);
|
||||
|
||||
int32_t wrap_18000(int32_t angle);
|
||||
int16_t wrap_180(int16_t angle);
|
||||
int32_t wrap_36000(int32_t angle);
|
||||
|
||||
int32_t quickMedianFilter3(int32_t * v);
|
||||
|
@ -191,6 +200,8 @@ float acos_approx(float x);
|
|||
void arraySubInt32(int32_t *dest, int32_t *array1, int32_t *array2, int count);
|
||||
|
||||
float bellCurve(const float x, const float curveWidth);
|
||||
float attenuation(const float input, const float width);
|
||||
float gaussian(const float x, const float mu, const float sigma);
|
||||
float fast_fsqrtf(const float value);
|
||||
float calc_length_pythagorean_2D(const float firstElement, const float secondElement);
|
||||
float calc_length_pythagorean_3D(const float firstElement, const float secondElement, const float thirdElement);
|
||||
|
|
|
@ -162,6 +162,7 @@ int tfp_nformat(void *putp, int size, void (*putf) (void *, char), const char *f
|
|||
written += putchw(putp, end, putf, w, lz, bf);
|
||||
break;
|
||||
}
|
||||
case 'i':
|
||||
case 'd':{
|
||||
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
|
||||
if (lng)
|
||||
|
|
|
@ -98,6 +98,11 @@ uint8_t sbufReadU8(sbuf_t *src)
|
|||
return *src->ptr++;
|
||||
}
|
||||
|
||||
int8_t sbufReadI8(sbuf_t *src)
|
||||
{
|
||||
return *src->ptr++;
|
||||
}
|
||||
|
||||
uint16_t sbufReadU16(sbuf_t *src)
|
||||
{
|
||||
uint16_t ret;
|
||||
|
|
|
@ -42,6 +42,7 @@ void sbufWriteU16BigEndian(sbuf_t *dst, uint16_t val);
|
|||
void sbufWriteU32BigEndian(sbuf_t *dst, uint32_t val);
|
||||
|
||||
uint8_t sbufReadU8(sbuf_t *src);
|
||||
int8_t sbufReadI8(sbuf_t *src);
|
||||
uint16_t sbufReadU16(sbuf_t *src);
|
||||
uint32_t sbufReadU32(sbuf_t *src);
|
||||
void sbufReadData(const sbuf_t *dst, void *data, int len);
|
||||
|
|
|
@ -29,6 +29,13 @@ typedef union {
|
|||
};
|
||||
} fpVector3_t;
|
||||
|
||||
typedef union {
|
||||
float v[2];
|
||||
struct {
|
||||
float x,y;
|
||||
};
|
||||
} fpVector2_t;
|
||||
|
||||
typedef struct {
|
||||
float m[3][3];
|
||||
} fpMat3_t;
|
||||
|
@ -116,3 +123,79 @@ static inline fpVector3_t * vectorScale(fpVector3_t * result, const fpVector3_t
|
|||
*result = ab;
|
||||
return result;
|
||||
}
|
||||
|
||||
static inline fpVector3_t* vectorSub(fpVector3_t* result, const fpVector3_t* a, const fpVector3_t* b)
|
||||
{
|
||||
fpVector3_t ab;
|
||||
|
||||
ab.x = a->x - b->x;
|
||||
ab.y = a->y - b->y;
|
||||
ab.z = a->z - b->z;
|
||||
|
||||
*result = ab;
|
||||
return result;
|
||||
}
|
||||
|
||||
static inline float vectorDotProduct(const fpVector3_t* a, const fpVector3_t* b)
|
||||
{
|
||||
return a->x * b->x + a->y * b->y + a->z * b->z;
|
||||
}
|
||||
|
||||
static inline float vector2NormSquared(const fpVector2_t * v)
|
||||
{
|
||||
return sq(v->x) + sq(v->y);
|
||||
}
|
||||
|
||||
static inline fpVector2_t* vector2Normalize(fpVector2_t* result, const fpVector2_t* v)
|
||||
{
|
||||
float sqa = vector2NormSquared(v);
|
||||
float length = sqrtf(sqa);
|
||||
if (length != 0) {
|
||||
result->x = v->x / length;
|
||||
result->y = v->y / length;
|
||||
} else {
|
||||
result->x = 0;
|
||||
result->y = 0;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
|
||||
static inline fpVector2_t* vector2Sub(fpVector2_t* result, const fpVector2_t* a, const fpVector2_t* b)
|
||||
{
|
||||
fpVector2_t ab;
|
||||
|
||||
ab.x = a->x - b->x;
|
||||
ab.y = a->y - b->y;
|
||||
|
||||
*result = ab;
|
||||
return result;
|
||||
}
|
||||
|
||||
static inline fpVector2_t * vector2Add(fpVector2_t * result, const fpVector2_t * a, const fpVector2_t * b)
|
||||
{
|
||||
fpVector2_t ab;
|
||||
|
||||
ab.x = a->x + b->x;
|
||||
ab.y = a->y + b->y;
|
||||
|
||||
*result = ab;
|
||||
return result;
|
||||
}
|
||||
|
||||
|
||||
static inline float vector2DotProduct(const fpVector2_t* a, const fpVector2_t* b)
|
||||
{
|
||||
return a->x * b->x + a->y * b->y;
|
||||
}
|
||||
|
||||
static inline fpVector2_t * vector2Scale(fpVector2_t * result, const fpVector2_t * a, const float b)
|
||||
{
|
||||
fpVector2_t ab;
|
||||
|
||||
ab.x = a->x * b;
|
||||
ab.y = a->y * b;
|
||||
|
||||
*result = ab;
|
||||
return result;
|
||||
}
|
||||
|
|
|
@ -64,7 +64,7 @@ static inline uint16_t pgIsProfile(const pgRegistry_t* reg) {return (reg->size &
|
|||
#ifdef __APPLE__
|
||||
extern const pgRegistry_t __pg_registry_start[] __asm("section$start$__DATA$__pg_registry");
|
||||
extern const pgRegistry_t __pg_registry_end[] __asm("section$end$__DATA$__pg_registry");
|
||||
#define PG_REGISTER_ATTRIBUTES __attribute__ ((section("__DATA,__pg_registry"), used, aligned(4)))
|
||||
#define PG_REGISTER_ATTRIBUTES __attribute__ ((section("__DATA,__pg_registry"), used, aligned(8)))
|
||||
|
||||
extern const uint8_t __pg_resetdata_start[] __asm("section$start$__DATA$__pg_resetdata");
|
||||
extern const uint8_t __pg_resetdata_end[] __asm("section$end$__DATA$__pg_resetdata");
|
||||
|
|
|
@ -126,7 +126,13 @@
|
|||
#define PG_FW_AUTOLAND_CONFIG 1036
|
||||
#define PG_FW_AUTOLAND_APPROACH_CONFIG 1037
|
||||
#define PG_OSD_CUSTOM_ELEMENTS_CONFIG 1038
|
||||
#define PG_INAV_END PG_OSD_CUSTOM_ELEMENTS_CONFIG
|
||||
#define PG_GIMBAL_CONFIG 1039
|
||||
#define PG_GIMBAL_SERIAL_CONFIG 1040
|
||||
#define PG_HEADTRACKER_CONFIG 1041
|
||||
#define PG_GEOZONE_CONFIG 1042
|
||||
#define PG_GEOZONES 1043
|
||||
#define PG_GEOZONE_VERTICES 1044
|
||||
#define PG_INAV_END PG_GEOZONE_VERTICES
|
||||
|
||||
// OSD configuration (subject to change)
|
||||
//#define PG_OSD_FONT_CONFIG 2047
|
||||
|
|
|
@ -214,6 +214,7 @@ bool bmi088AccDetect(accDev_t *acc)
|
|||
|
||||
acc->initFn = bmi088AccInit;
|
||||
acc->readFn = bmi088AccRead;
|
||||
acc->accAlign = acc->busDev->param;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -108,15 +108,6 @@ static const gyroFilterAndRateConfig_t gyroConfigs[] = {
|
|||
{ GYRO_LPF_256HZ, 3200, { BMI160_BWP_OSR4 | BMI160_ODR_3200_Hz} },
|
||||
{ GYRO_LPF_256HZ, 1600, { BMI160_BWP_OSR2 | BMI160_ODR_1600_Hz} },
|
||||
{ GYRO_LPF_256HZ, 800, { BMI160_BWP_NORMAL | BMI160_ODR_800_Hz } },
|
||||
|
||||
{ GYRO_LPF_188HZ, 800, { BMI160_BWP_OSR2 | BMI160_ODR_800_Hz } }, // ODR = 800 Hz, LPF = 128 Hz
|
||||
{ GYRO_LPF_188HZ, 400, { BMI160_BWP_NORMAL | BMI160_ODR_400_Hz } }, // ODR = 400 Hz, LPF = 137 Hz
|
||||
|
||||
{ GYRO_LPF_98HZ, 800, { BMI160_BWP_OSR4 | BMI160_ODR_800_Hz } }, // ODR = 800 Hz, LPF = 63 Hz
|
||||
{ GYRO_LPF_98HZ, 400, { BMI160_BWP_OSR2 | BMI160_ODR_400_Hz } }, // ODR = 400 Hz, LPF = 68 Hz
|
||||
|
||||
{ GYRO_LPF_42HZ, 800, { BMI160_BWP_OSR4 | BMI160_ODR_800_Hz } }, // ODR = 800 Hz, LPF = 63 Hz
|
||||
{ GYRO_LPF_42HZ, 400, { BMI160_BWP_OSR4 | BMI160_ODR_400_Hz } }, // ODR = 400 Hz, LPF = 34 Hz
|
||||
};
|
||||
|
||||
static void bmi160AccAndGyroInit(gyroDev_t *gyro)
|
||||
|
|
|
@ -134,15 +134,6 @@ static const gyroFilterAndRateConfig_t gyroConfigs[] = {
|
|||
{ GYRO_LPF_256HZ, 3200, { BMI270_BWP_OSR4 | BMI270_ODR_3200} },
|
||||
{ GYRO_LPF_256HZ, 1600, { BMI270_BWP_OSR2 | BMI270_ODR_1600} },
|
||||
{ GYRO_LPF_256HZ, 800, { BMI270_BWP_NORM | BMI270_ODR_800 } },
|
||||
|
||||
{ GYRO_LPF_188HZ, 800, { BMI270_BWP_OSR2 | BMI270_ODR_800 } },
|
||||
{ GYRO_LPF_188HZ, 400, { BMI270_BWP_NORM | BMI270_ODR_400 } },
|
||||
|
||||
{ GYRO_LPF_98HZ, 800, { BMI270_BWP_OSR4 | BMI270_ODR_800 } },
|
||||
{ GYRO_LPF_98HZ, 400, { BMI270_BWP_OSR2 | BMI270_ODR_400 } },
|
||||
|
||||
{ GYRO_LPF_42HZ, 800, { BMI270_BWP_OSR4 | BMI270_ODR_800 } },
|
||||
{ GYRO_LPF_42HZ, 400, { BMI270_BWP_OSR4 | BMI270_ODR_400 } },
|
||||
};
|
||||
|
||||
// Toggle the CS to switch the device into SPI mode.
|
||||
|
|
|
@ -62,6 +62,7 @@
|
|||
|
||||
#define ICM42605_RA_GYRO_DATA_X1 0x25
|
||||
#define ICM42605_RA_ACCEL_DATA_X1 0x1F
|
||||
#define ICM42605_RA_TEMP_DATA1 0x1D
|
||||
|
||||
#define ICM42605_RA_INT_CONFIG 0x14
|
||||
#define ICM42605_INT1_MODE_PULSED (0 << 2)
|
||||
|
@ -198,21 +199,6 @@ static const gyroFilterAndRateConfig_t icm42605GyroConfigs[] = {
|
|||
{ GYRO_LPF_256HZ, 2000, { 3, 5 } }, /* 250 Hz LPF */
|
||||
{ GYRO_LPF_256HZ, 1000, { 1, 6 } }, /* 250 Hz LPF */
|
||||
{ GYRO_LPF_256HZ, 500, { 0, 15 } }, /* 250 Hz LPF */
|
||||
|
||||
{ GYRO_LPF_188HZ, 1000, { 3, 6 } }, /* 125 HZ */
|
||||
{ GYRO_LPF_188HZ, 500, { 1, 15 } }, /* 125 HZ */
|
||||
|
||||
{ GYRO_LPF_98HZ, 1000, { 4, 6 } }, /* 100 HZ*/
|
||||
{ GYRO_LPF_98HZ, 500, { 2, 15 } }, /* 100 HZ*/
|
||||
|
||||
{ GYRO_LPF_42HZ, 1000, { 6, 6 } }, /* 50 HZ */
|
||||
{ GYRO_LPF_42HZ, 500, { 4, 15 } },
|
||||
|
||||
{ GYRO_LPF_20HZ, 1000, { 7, 6 } }, /* 25 HZ */
|
||||
{ GYRO_LPF_20HZ, 500, { 6, 15 } },
|
||||
|
||||
{ GYRO_LPF_10HZ, 1000, { 7, 6 } }, /* 25 HZ */
|
||||
{ GYRO_LPF_10HZ, 500, { 7, 15 } } /* 12.5 HZ */
|
||||
};
|
||||
|
||||
static void icm42605AccAndGyroInit(gyroDev_t *gyro)
|
||||
|
@ -336,6 +322,20 @@ static bool icm42605GyroRead(gyroDev_t *gyro)
|
|||
return true;
|
||||
}
|
||||
|
||||
static bool icm42605ReadTemperature(gyroDev_t *gyro, int16_t * temp)
|
||||
{
|
||||
uint8_t data[2];
|
||||
|
||||
const bool ack = busReadBuf(gyro->busDev, ICM42605_RA_TEMP_DATA1, data, 2);
|
||||
if (!ack) {
|
||||
return false;
|
||||
}
|
||||
// From datasheet: Temperature in Degrees Centigrade = (TEMP_DATA / 132.48) + 25
|
||||
*temp = ( int16_val_big_endian(data, 0) / 13.248 ) + 250; // Temperature stored as degC*10
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool icm42605GyroDetect(gyroDev_t *gyro)
|
||||
{
|
||||
gyro->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_ICM42605, gyro->imuSensorToUse, OWNER_MPU);
|
||||
|
@ -355,7 +355,7 @@ bool icm42605GyroDetect(gyroDev_t *gyro)
|
|||
gyro->initFn = icm42605AccAndGyroInit;
|
||||
gyro->readFn = icm42605GyroRead;
|
||||
gyro->intStatusFn = gyroCheckDataReady;
|
||||
gyro->temperatureFn = NULL;
|
||||
gyro->temperatureFn = icm42605ReadTemperature;
|
||||
gyro->scale = 1.0f / 16.4f; // 16.4 dps/lsb scalefactor
|
||||
gyro->gyroAlign = gyro->busDev->param;
|
||||
|
||||
|
|
|
@ -50,21 +50,6 @@ static const gyroFilterAndRateConfig_t mpuGyroConfigs[] = {
|
|||
{ GYRO_LPF_256HZ, 1000, { MPU_DLPF_256HZ, 7 } },
|
||||
{ GYRO_LPF_256HZ, 666, { MPU_DLPF_256HZ, 11 } },
|
||||
{ GYRO_LPF_256HZ, 500, { MPU_DLPF_256HZ, 15 } },
|
||||
|
||||
{ GYRO_LPF_188HZ, 1000, { MPU_DLPF_188HZ, 0 } },
|
||||
{ GYRO_LPF_188HZ, 500, { MPU_DLPF_188HZ, 1 } },
|
||||
|
||||
{ GYRO_LPF_98HZ, 1000, { MPU_DLPF_98HZ, 0 } },
|
||||
{ GYRO_LPF_98HZ, 500, { MPU_DLPF_98HZ, 1 } },
|
||||
|
||||
{ GYRO_LPF_42HZ, 1000, { MPU_DLPF_42HZ, 0 } },
|
||||
{ GYRO_LPF_42HZ, 500, { MPU_DLPF_42HZ, 1 } },
|
||||
|
||||
{ GYRO_LPF_20HZ, 1000, { MPU_DLPF_20HZ, 0 } },
|
||||
{ GYRO_LPF_20HZ, 500, { MPU_DLPF_20HZ, 1 } },
|
||||
|
||||
{ GYRO_LPF_10HZ, 1000, { MPU_DLPF_10HZ, 0 } },
|
||||
{ GYRO_LPF_10HZ, 500, { MPU_DLPF_10HZ, 1 } }
|
||||
};
|
||||
|
||||
const gyroFilterAndRateConfig_t * mpuChooseGyroConfig(uint8_t desiredLpf, uint16_t desiredRateHz)
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show more
Loading…
Add table
Add a link
Reference in a new issue